HKUST-Aerial-Robotics / ESVO

This repository maintains the implementation of "Event-based Stereo Visual Odometry".
433 stars 92 forks source link

DSEC dataset parameters #14

Closed ahadviger closed 3 years ago

ahadviger commented 3 years ago

Hello,

I am trying to get results with ESVO on the new DSEC dataset (http://rpg.ifi.uzh.ch/dsec.html). The dataset has 640x480 resolution and stereo baseline of 60 cm. The event rate is significantly higher than of MVSEC and other referenced datasets, so I tried to tune the parameters accordingly. I manage to get good mapping initialization with SGM (thousands of points):

Selection_116

Afterwards, I get very few points in the pointcloud: Selection_117

Here are the tracking and mapping parameters I am currently using: invDepth_min_range: 0.005 invDepth_max_range: 0.5 TS_HISTORY_LENGTH: 100 REF_HISTORY_LENGTH: 10 tracking_rate_hz: 100 patch_size_X: 1 patch_size_Y: 1 kernelSize: 5 MAX_REGISTRATION_POINTS: 2000 BATCH_SIZE: 300 MAX_ITERATION: 10 LSnorm: Huber #Huber #l2 huber_threshold: 50 MIN_NUM_EVENTS: 1000 RegProblemType: 1 #( 0 numerical; 1 analytical) SAVE_TRAJECTORY: False PATH_TO_SAVE_TRAJECTORY: "/home/antea/main_ws/src/ESVO" # CHANGE THIS PATH VISUALIZE_TRAJECTORY: True

invDepth_min_range: 0.005 invDepth_max_range: 0.5 residual_vis_threshold: 20 stdVar_vis_threshold: 0.15 age_max_range: 10 age_vis_threshold: 1 fusion_radius: 0 FUSION_STRATEGY: "CONST_FRAMES" # "CONST_FRAMES" maxNumFusionFrames: 40 maxNumFusionPoints: 2000 Denoising: False SmoothTimeSurface: False Regularization: False bVisualizeGlobalPC: True visualizeGPC_interval: 1 NumGPC_added_oper_refresh: 3000 visualize_range: 5.0 PROCESS_EVENT_NUM: 5000 TS_HISTORY_LENGTH: 100 INIT_SGM_DP_NUM_THRESHOLD: 500 mapping_rate_hz: 10

DepthProblemConfig patch_size_X: 15 patch_size_Y: 7 LSnorm: Tdist # l2 Tdist_nu: 2.182 Tdist_scale: 17.277 Tdist_stdvar: 59.763

EventBM parameters BM_half_slice_thickness: 0.001 BM_min_disparity: 1 BM_max_disparity: 100 BM_step: 1 BM_ZNCC_Threshold: 0.1 BM_bUpDownConfiguration: False

If it helps, I can provide a rosbag with a sample of this dataset. Any suggestions would be helpful, thanks!

Ethan-Zhou commented 3 years ago

Hi, could you please provide the code for generating rosbags from h5 files? Then I will give it a try. Thx.

发自我的iPhone

在 2021年5月5日,上午1:27,Antea Hadviger @.***> 写道:

 Hello,

I am trying to get results with ESVO on the new DSEC dataset (http://rpg.ifi.uzh.ch/dsec.html). The dataset has 640x480 resolution and stereo baseline of 60 cm. The event rate is significantly higher than of MVSEC and other referenced datasets, so I tried to tune the parameters accordingly. I manage to get good mapping initialization with SGM (thousands of points):

Afterwards, I get very few points in the pointcloud:

Here are the tracking and mapping parameters I am currently using: invDepth_min_range: 0.005 invDepth_max_range: 0.5 TS_HISTORY_LENGTH: 100 REF_HISTORY_LENGTH: 10 tracking_rate_hz: 100 patch_size_X: 1 patch_size_Y: 1 kernelSize: 5 MAX_REGISTRATION_POINTS: 2000 BATCH_SIZE: 300 MAX_ITERATION: 10 LSnorm: Huber #Huber #l2 huber_threshold: 50 MIN_NUM_EVENTS: 1000 RegProblemType: 1 #( 0 numerical; 1 analytical) SAVE_TRAJECTORY: False PATH_TO_SAVE_TRAJECTORY: "/home/antea/main_ws/src/ESVO" # CHANGE THIS PATH VISUALIZE_TRAJECTORY: True

invDepth_min_range: 0.005 invDepth_max_range: 0.5 residual_vis_threshold: 20 stdVar_vis_threshold: 0.15 age_max_range: 10 age_vis_threshold: 1 fusion_radius: 0 FUSION_STRATEGY: "CONST_FRAMES" # "CONST_FRAMES" maxNumFusionFrames: 40 maxNumFusionPoints: 2000 Denoising: False SmoothTimeSurface: False Regularization: False bVisualizeGlobalPC: True visualizeGPC_interval: 1 NumGPC_added_oper_refresh: 3000 visualize_range: 5.0 PROCESS_EVENT_NUM: 5000 TS_HISTORY_LENGTH: 100 INIT_SGM_DP_NUM_THRESHOLD: 500 mapping_rate_hz: 10

DepthProblemConfig patch_size_X: 15 patch_size_Y: 7 LSnorm: Tdist # l2 Tdist_nu: 2.182 Tdist_scale: 17.277 Tdist_stdvar: 59.763

EventBM parameters BM_half_slice_thickness: 0.001 BM_min_disparity: 1 BM_max_disparity: 100 BM_step: 1 BM_ZNCC_Threshold: 0.1 BM_bUpDownConfiguration: False

If it helps, I can provide a rosbag with a sample of this dataset. Any suggestions would be helpful, thanks!

— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub, or unsubscribe.

ahadviger commented 3 years ago

Sure, here is the code: https://gist.github.com/ahadviger/4510bb3ea3fcdb35729c33390d4f9d14 I found it runs quicker if I choose a fixed number of events to wrap in a single message, and then use your C++ code to get 1000 Hz, as opposed to getting a 1000 Hz frequency directly with this code.

Ethan-Zhou commented 3 years ago

Hi, I came across a problem when using your parsing code. It's stuck in Line 41 "for x, y, t, p in zip(np_x, np_y, np_t, np_p):". Could you show me how to solve this problem? Sorry for not being familiar with python.

On Wed, 5 May 2021 at 22:16, Antea Hadviger @.***> wrote:

Sure, here is the code: https://gist.github.com/ahadviger/4510bb3ea3fcdb35729c33390d4f9d14 I found it runs quicker if I choose a fixed number of events to wrap in a single message, and then use your C++ code to get 1000 Hz, as opposed to getting a 1000 Hz frequency directly with this code.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/HKUST-Aerial-Robotics/ESVO/issues/14#issuecomment-832724478, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABJEH4B5PEPUD77OMN4WT3LTMFHNLANCNFSM44DEAMBA .

ahadviger commented 3 years ago

Hi, this code can take some time to run since the h5 files are fairly large, so I assume that is why it seems like it's stuck. Here are the launch and calib files and a sample rosbag of zurich_city_04_b sequence: zurich_city_04_b.zip https://www.dropbox.com/s/a60r5mmns8n2k4h/zurich_city_04_b_events.bag?dl=0

Ethan-Zhou commented 3 years ago

Hi,

Well, I might be more patient. I gave it up because the programme was still stuck in the zip() function after 10 mins had passed. Thanks for your data anyway. I will give it a try.

BTW, two things before I try: 1) I noticed you raised an issue on DSEC's github page. Do you still think the rectified maps are not correct? 2) Have you added the time offset to the events' timestamp? Do you think this may cause anything wrong?

Cheers

On Thu, 6 May 2021 at 18:13, Antea Hadviger @.***> wrote:

Hi, this code can take some time to run since the h5 files are fairly large, so I assume that is why it seems like it's stuck. Here are the launch and calib files and a sample rosbag of zurich_city_04_b sequence: zurich_city_04_b.zip https://github.com/HKUST-Aerial-Robotics/ESVO/files/6433661/zurich_city_04_b.zip https://www.dropbox.com/s/a60r5mmns8n2k4h/zurich_city_04_b_events.bag?dl=0

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/HKUST-Aerial-Robotics/ESVO/issues/14#issuecomment-833408075, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABJEH4APE3BJOBS57F5Y7VLTMJTVXANCNFSM44DEAMBA .

ahadviger commented 3 years ago

1) Yes, I had issues with the precomputed rectification maps (I probably made some mistake during processing since the authors did not have the same problem), but the yaml calibration files should be correct. 2) I used the original timestamps from the h5 files which start from zero, do you think I should have added the offset? I'm not sure how this would make any difference anyway.

Thanks!

Ethan-Zhou commented 3 years ago

Hi @ahadviger, I finally found the problem that induced the mapping failure. If you look at https://github.com/HKUST-Aerial-Robotics/ESVO/blob/2dc7a91a9ad54eb6f05ee63602a9fa6e76cbed75/esvo_core/src/core/DepthProblemSolver.cpp#L192 you see I made a handy bound for the optimization which limits the range. To enable ESVO to "see" further, simply reduce 0.1 to e.g., 0.001. I will make this a global paramter in the upcoming commit. Thank you for the rosbag file transformed from h5 format. May I ask you to create another one for me? The current one consists of several moving objects which fails ESVO at the end of the sequence. I want to do some further fine tuning on a static scene. Thanks a lot. Cheers, yi

ahadviger commented 3 years ago

Great that you figured it out! I totally missed this. These are two longer sequences: zurich_city_04_a and zurich_city_04_e (this one is not at 1000 Hz, I think). Calibration is different than the one I previously sent, but you can find the parameters on the DSEC website.

Best, Antea

Ethan-Zhou commented 3 years ago

Hi @ahadviger , Please try my new commit. Just go to ~/launch/system/DSEC/system_zurich_city_04_a.launch for the example. The rosbag play can be found in the corresponding directory under esvo_time_surface package as usual. Thank you for generating the rosbag, which saves me a lot of time. Also, please note that the calibration you provided before is not fully correct. You may check yours against what I uploaded. Note that I have to play the rosbag pretty slow this time because of 1) the higher spatial resolution (approximately 4x larger than DAVIS 346), 2) the fast speed of the vehicle and 3) the limited comutational resouces on my laptop. Please feel free to report any problem on your side. Cheers, yi

Ethan-Zhou commented 3 years ago

A demo can be found at https://youtu.be/NByVeO4Ss5o..