HKUST-Aerial-Robotics/open_quadtree_mapping

System didnt work on my bag( just several depth image in long period)

FrozenBurning opened this issue · 23 comments

Hi!
Thanks for your great works in advance. Here I encounter some problems that the system seemed not work well while I test it on my bag.
quad
Here 's a shot of the situation, according to some previous issues, I checked my bag and it have the accurate frequency of camera pose and image(for vins_estimator/camera_pose in 18-20Hz & mv_26801267/image_raw for 40Hz)

I think the camera pose is accurate enough by vins_fusion, for the path is align to the ground truth. And there's not much rotation of camera in my bag, and the resolution of image is 752 x 480 which is enough (maybe?).
But I just get 2~3 depth images through the whole bag (shown above) ! I dont know what's wrong with it. Any suggestion?

Hi,
I looked at the image but cannot find anything suspicious. What's the semi2dense_ratio? Or you can provide the launch file here.
Kaixuan

<param name="cam_width" value="752" />
<param name="cam_height" value="480" />
<param name="cam_fx" value="7.0415625995862342e+02" />
<param name="cam_cx" value="3.4195262533917793e+02" />
<param name="cam_fy" value="7.0248181078535049e+02" />
<param name="cam_cy" value="2.3355271016158875e+02" />
<param name="cam_k1" value="-5.1296624590990725e-01"/>
<param name="cam_k2" value="3.2427347635939696e-01"/>
<param name="cam_r1" value="4.72342533405994780e-03"/>
<param name="cam_r2" value="-4.9104770208680654e-04"/>
<!--downsample factor: 0 ~ 1-->
<param name="downsample_factor" value="1"/>
<param name="semi2dense_ratio" value="1"/>

<!-- if using synchronize image and pose-->
<remap from="~image" to="/mv_26801267/image_raw" />
<remap from="~odometry" to="/vins_estimator/camera_pose" />

here is the launch file, I only modified the params of camera from the original one

Well, it seems all right...
Would you please try to downsize the image (downsample_factor = 0.5) so that maybe the GPU RAM usage can be lowered. (I notice you are using a laptop?).
Please tell me if it works.

Actually, I'm using the cpu version now.
I'll try to downsize the image, if it didnt work yet I would try the cuda version

CPU version?
Actually, it does not matter too much. Do you mean you do not have CUDA? (I think if you do not have CUDA you cannot run the code...)

I have cuda10.0.
I mean, I used the branch nocudaopencv, not the master one. I figure it out in case there is some optimization in your code between the two different versions.

And, after downsizing the image(to 0.5), I got 7 depth images with the same bag... better than only 2-3 depth images :)
I also monitor the GPU memory usage when it's running, it's around 600MB/2000MB.

Well... I really do not understand why it happens.
Since you can run the example, I think it is not your machine/environment problem.
Actually, the movement and the calibration only affect the quality of the depth maps, not the image numbers. Even if you are moving aggressively (or bad VINS quality), you should get many (the same as frame rate) depth maps.
Is the quadtree log refresh rate the same as image rate?

quadtree log means the terminal output while I run the quadtree node? Actually, I just count the number of image from that log. In other words, it only refreshed 7 times(output some time costs info) in my previous try. when using rostopic hz to see the frequency, the depth image topic always show "no new message".

From the log, I think

bool quadmap::SeedMatrix::need_add_reference()
is always giving false such that you do not have enough frames to estimate the depth map.

Can you add:
printf(" we have %d frames.\n", framelist_host.size());
right after this line?

bool has_depth_output = false;

Rebuild the package and give me the log file.

Here you are

CLEAR PARAMETERS

  • /open_quadtree_mapping/

PARAMETERS

  • /open_quadtree_mapping/cam_cx: 341.952625339
  • /open_quadtree_mapping/cam_cy: 233.552710162
  • /open_quadtree_mapping/cam_fx: 704.156259959
  • /open_quadtree_mapping/cam_fy: 702.481810785
  • /open_quadtree_mapping/cam_height: 480
  • /open_quadtree_mapping/cam_k1: -0.51296624591
  • /open_quadtree_mapping/cam_k2: 0.324273476359
  • /open_quadtree_mapping/cam_r1: 0.00472342533406
  • /open_quadtree_mapping/cam_r2: -0.000491047702087
  • /open_quadtree_mapping/cam_width: 752
  • /open_quadtree_mapping/downsample_factor: 0.5
  • /open_quadtree_mapping/semi2dense_ratio: 1
  • /rosdistro: melodic
  • /rosversion: 1.14.3

NODES
/
open_quadtree_mapping (open_quadtree_mapping/open_quadtree_mapping_node)

auto-starting new master
process[master]: started with pid [22317]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 5165fde8-5b9e-11e9-acd0-dc5360731b58
process[rosout-1]: started with pid [22328]
started core service [/rosout]
process[open_quadtree_mapping-2]: started with pid [22336]
Running executable: /home/royubuntu/quadtree_mapping/devel/lib/open_quadtree_mapping/open_quadtree_mapping_node
Checking available CUDA-capable devices...
1 CUDA-capable GPU detected:
Device 0 - GeForce GTX 960M
Using GPU device 0: "GeForce GTX 960M" with compute capability 5.0
GPU device 0 has 5 Multi-Processors, SM 5.0 compute capabilities

read : width 752 height 480
has success set cuda remap.
inremap_2itial the seed (376 x 240) fx: 352.078125, fy: 351.240906, cx: 170.976318, cy: 116.776352.
initial the publisher !

cuda prepare the image cost 1.201000 ms
till add image cost 0.529000 ms
initialize keyframe cost 0.224000 ms
depthimage min max of the depth: 0 , 0
INFO: publishing depth map

cuda prepare the image cost 0.723000 ms
till add image cost 0.246000 ms
till all semidense cost 5.958000 ms
we have 0 frames.
till all full dense cost 0.005000 ms
till all end cost 0.303000 ms

cuda prepare the image cost 1.330000 ms
till add image cost 0.498000 ms
till all semidense cost 2.815000 ms
we have 1 frames.
till all full dense cost 0.005000 ms
till all end cost 0.081000 ms

cuda prepare the image cost 1.067000 ms
till add image cost 0.251000 ms
till all semidense cost 6.041000 ms
we have 2 frames.
till all full dense cost 0.003000 ms
till all end cost 0.325000 ms

cuda prepare the image cost 1.442000 ms
till add image cost 4.792000 ms
till all semidense cost 3.019000 ms
we have 3 frames.
till all full dense cost 0.006000 ms
till all end cost 0.068000 ms

cuda prepare the image cost 1.182000 ms
till add image cost 0.194000 ms
till all semidense cost 6.197000 ms
we have 4 frames.
till all full dense cost 0.004000 ms
till all end cost 0.318000 ms

cuda prepare the image cost 0.926000 ms
till add image cost 4.406000 ms
till all semidense cost 4.309000 ms
we have 5 frames.
till all full dense cost 0.003000 ms
till all end cost 0.072000 ms

it only refreshed 7 times(output some time costs info)

Ok, please check the VINS camera pose time stamp and the image time stamp.
I think they are not exactly the same.
VINS has been modified a lot since I published open_quadtree mapping. The time stamp from the current VINS may not be exactly the same as the input image.

Please check the time stamp.

time_delay
as you say, I think it might be the problem. on the left is image_raw and the right one is camera_pose, using rostopic delay. Seemed that there's unbearable unsync between them.

I mean you can
rostopic echo **(image_name)**.header.stamp
and
rostopic echo **(pose_name)**.header.stamp
to check if they are exactly the same.
I am not sure what delay it stands for...

from your method rostopic echo, I can only got the pose's time stamp, but the image only show the voxel matrix on screen.
The delay shown above should be standing on the same header.

Good news.
As I sync the timestamp between image and pose, it work properly, and I got quanlified depth image around 10Hz. So your work require strict sync between image and pose, or it will failed.

THANKS A LOT FOR HELPING ME OUT!
Also Thank your amazing works. Sorry for disturbing till night.

Glad that it works.

hello I guess I met the same question with you,when I run vins-mono, it runs normally, but when I run vins-fusion ,the open_quadtree_mapping dose not respond,I don't know if it's not synchronized,How did you solve it, can you tell me in detail, thank you

hello I guess I met the same question with you,when I run vins-mono, it runs normally, but when I run vins-fusion ,the open_quadtree_mapping dose not respond,I don't know if it's not synchronized,How did you solve it, can you tell me in detail, thank you

Sorry for updating late. Are you still troubled by it?

No, when I run open_quadtree with vins mono, deep topics can appear, but not with vins fusion. I think you said that you need to align the timestamps of the two topics of image and pose. I do n’t know if my method is correct, Can you show it to me, thank you

Since it's long time ago when I get involved into this issue, I can't recall the details. I think you can try VINS-Mono instead of VINS-Fusion. Actually, there are some differences in code implementation between them, which results into little lag behind the camera frames in VINS-Fusion.