Skip to content

Commit

Permalink
documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
zhangzichao committed Aug 18, 2017
1 parent 6918b16 commit 4bc76a7
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 4 deletions.
18 changes: 18 additions & 0 deletions svo_ros/doc/euroc.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
We provide two launch files for [EuRoC](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) for monocular and stereo setups:

roslaunch svo_ros euroc_mono_imu.launch
roslaunch svo_ros euroc_stereo_imu.launch

These launch files read the parameters from `param/euroc_mono_imu.yaml` and `param/euroc_stereo_imu.yaml`. The parameters are not necessarily optimal for every sequence, but should be enough as a good starting point.

### Staring Position when Playing Bag
The first several images of many EuRoC sequences are not good for initialize `SVO`, especially for the monocular case. Therefore it is better to start the bag at a later time, for example:

rosbag play MH_01_easy.bag -s 50
rosbag play MH_02_easy.bag -s 45
rosbag play V1_01_easy.bag
rosbag play V1_02_medium.bag -s 13
rosbag play V2_01_easy.bag
rosbag play V2_02_medium.bag -s 13

This is to avoid, for example, strong rotation for monocular initialization.
7 changes: 4 additions & 3 deletions svo_ros/param/euroc_mono_imu.yaml
Original file line number Diff line number Diff line change
@@ -1,13 +1,14 @@
grid_size: 35
use_threaded_depthfilter: False
use_imu: True
poseoptim_prior_lambda: 0.0
img_align_prior_lambda_rot: 0.5
img_align_prior_lambda_trans: 0.0

# if the number of features are below this number, consider as failure
# If set to false, we process the next frame(s) only when the depth update is finished
use_threaded_depthfilter: False
# If the number of features are below this number, consider as failure
quality_min_fts: 40
# if the number of features reduce by this number for consecutive frames, consider as failure
# If the number of features reduce by this number for consecutive frames, consider as failure
quality_max_drop_fts: 80

map_scale: 5.0
Expand Down
3 changes: 2 additions & 1 deletion svo_ros/param/euroc_stereo_imu.yaml
Original file line number Diff line number Diff line change
@@ -1,13 +1,14 @@
pipeline_is_stereo: True

grid_size: 35
use_threaded_depthfilter: False
use_async_reprojectors: True
use_imu: False
poseoptim_prior_lambda: 0.0
img_align_prior_lambda_rot: 0.0
img_align_prior_lambda_trans: 0.0

# If set to false, we process the next frame(s) only when the depth update is finished
use_threaded_depthfilter: False
# if the number of features are below this number, consider as failure
quality_min_fts: 40
# if the number of features reduce by this number for consecutive frames, consider as failure
Expand Down

0 comments on commit 4bc76a7

Please sign in to comment.