Re: Outdoor Localization error while running zed-ros-examples using zed2i camera
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Outdoor-Localization-error-while-running-zed-ros-examples-using-zed2i-camera-tp9773p9804.html
Hi,
Another issue I see in the bags is that in the localization bag, the image resolution is 2X the resolution in the mapping bag. The features (BRIEF) used by default are not very scale invariant, so doubling the resolution will generate very low matches and loop closure hypotheses would be very low. I based my examples below from this
tutorial.
For the mapping bag, we have to remove the "map" frame in /tf topic before reprocessing it (based on this
post), then:
roslaunch rtabmap_launch rtabmap.launch \
rtabmap_args:="--delete_db_on_start --Vis/CorFlowMaxLevel 5 --Stereo/MaxDisparity 200" \
stereo_namespace:=/zed/zed_node \
right_image_topic:=/zed/zed_node/right/image_rect_gray \
stereo:=true \
visual_odometry:=false \
frame_id:=base_link \
odom_frame_id:=odom \
imu_topic:=/zed/zed_node/imu/data \
wait_imu_to_init:=true \
use_sim_time:=true
rosbag play --clock MAPPING.bag
For the localization bag, we have to decimate the input images, and I also needed to remove "map" and "odom" frames as odom framerate recorded in that bag is slow, so I recomputed odometry on my side (not that odometry is not that nice as it is only done at 1 Hz, but was okay to test):
roslaunch rtabmap_launch rtabmap.launch \
rtabmap_args:="--Vis/CorFlowMaxLevel 5 --Stereo/MaxDisparity 200 --Mem/ImagePreDecimation 2 --Mem/ImagePostDecimation 2" \
stereo_namespace:=/zed/zed_node \
right_image_topic:=/zed/zed_node/right/image_rect_gray \
stereo:=true \
visual_odometry:=true \
frame_id:=base_link \
imu_topic:=/zed/zed_node/imu/data \
wait_imu_to_init:=true \
localization:=true \
use_sim_time:=true
rosbag play --clock localization.bag
There is localization on almost every frame.

To use stereo with
zed-ros-examples, you will have to change under rtabmap and rtabmap_viz this:
<remap from="rgb/image" to="$(arg rgb_topic)"/>
<remap from="depth/image" to="$(arg depth_topic)"/>
<remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
by this:
<param name="subscribe_stereo" value="true""/>
<remap from="left/image_rect" to="/zed/zed_node/left/image_rect_color"/>
<remap from="right/image_rect" to="/zed/zed_node/right/image_rect_gray"/>
<remap from="left/camera_info" to="/zed/zed_node/left/camera_info"/>
<remap from="right/camera_info" to="/zed/zed_node/right/camera_info"/>