ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

rtabmap localization

asked 2018-09-07 09:22:40 -0500

rembert gravatar image

Hi

I'm trying to run rtabmap in localization mode.

This is my launch file:

<launch>
<arg name="localization" value="true"/>

<arg     if="$(arg localization)" name="rtabmap_args"  default=""/>
<arg unless="$(arg localization)" name="rtabmap_args"  default="--delete_db_on_start"/>

<node pkg="tf2_ros" type="static_transform_publisher" name="camera_broadcaster" args="0.613 0.012 0.425 0.002 0.008 -0.010 1.000 base_link camera_link" />
<node pkg="tf2_ros" type="static_transform_publisher" name="footprint_broadcaster" args="0 0 0.125 0 0 0 1 base_footprint base_link" />

<param name="robot_description" textfile="$(find robot_slam)/urdf/robot.urdf" />

<node pkg="robot_slam" name="control" type="control.py" output="screen">
</node>

<!-- ROS navigation stack move_base -->
<group ns="planner">
    <remap from="point_cloud" to="/planner/planner_cloud"/>
    <remap from="map" to="/rtabmap/grid_map"/>
    <remap from="move_base_simple/goal" to="/move_base_simple/goal"/>

    <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
        <rosparam file="$(find robot_slam)/launch/config/move_base/costmap_common.yaml" command="load" ns="global_costmap" />
        <rosparam file="$(find robot_slam)/launch/config/move_base/costmap_common.yaml" command="load" ns="local_costmap" />
        <rosparam file="$(find robot_slam)/launch/config/move_base/costmap_local.yaml" command="load" />
        <rosparam file="$(find robot_slam)/launch/config/move_base/costmap_global.yaml" command="load"/>
        <rosparam file="$(find robot_slam)/launch/config/move_base/base_local_planner.yaml" command="load" />
    </node>
</group>

<!-- encoder odometry -->
<node pkg="robot_slam" name="encoder_odometry" type="odometry.py" output="screen">
    <remap from="odom" to="/planner/odom"/>

    <param name="odom_frame_id" type="string" value="odom"/>
    <param name="robot_frame_id" type="string" value="base_footprint"/>
</node>

<group ns="rtabmap">
    <!-- RGB-D Odometry -->
    <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="log">
        <remap from="rgb/image"       to="/camera/color/image_raw"/>
        <remap from="depth/image"     to="/camera/aligned_depth_to_color/image_raw"/>
        <remap from="rgb/camera_info" to="/camera/color/camera_info"/>
        <remap from="rgbd_image"      to="rgbd_image"/>
        <remap from="odom"            to="rgbd_odom"/>

        <param name="frame_id"                    type="string" value="base_footprint"/>
        <param name="odom_frame_id"               type="string" value="odom"/>
        <param name="publish_tf"                  type="bool"   value="true"/>
        <param name="ground_truth_frame_id"       type="string" value=""/>
        <param name="ground_truth_base_frame_id"  type="string" value=""/>
        <param name="wait_for_transform"          type="bool"   value="true"/>
        <param name="wait_for_transform_duration" type="double" value="0.2"/>
        <param name="approx_sync"                 type="bool"   value="false"/>
        <param name="config_path"                 type="string" value=""/>
        <param name="queue_size"                  type="int"    value="10"/>
        <param name="subscribe_rgbd"              type="bool"   value="false"/>
        <param name="guess_frame_id"              type="string" value=""/>
        <param name="guess_min_translation"       type="double" value="0"/>
        <param name="guess_min_rotation"          type="double" value="0"/>

        <param name="Odom/ResetCountdown"         type="int"    value="10"/>
        <param name="Odom/Holonomic" type="bool" value="false"/>
        <param name="Vis/MaxFeatures" type="string" value="1000"/>
        <param name="Reg/Force3DoF"             type="bool" value="false"/>

        <param name="RGBD/SavedLocalizationIgnored" type="bool" value="true"/>
    </node>

    <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" args="$(arg rtabmap_args)" output="log">
        <param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
        <param if="$(arg localization)" name="Mem/InitWMWithAllNodes" type="string" value="true"/>

        <remap from="odom" to="/rtabmap/rgbd_odom"/> 
        <remap from="rgb/image" to="/camera/color/image_raw"/>
        <remap from="depth/image" to="/camera/aligned_depth_to_color/image_raw"/>
        <remap from="rgb/camera_info" to="/camera/color/camera_info"/>

        <param name="frame_id"          type="string"   value="base_footprint"/>
        <param name="odom_frame_id"     type="string"   value="odom"/>
        <param name="map_frame_id"      type="string"   value="map"/>
        <param name ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-09-07 13:39:40 -0500

matlabbe gravatar image

Hi,

<param name="RGBD/SavedLocalizationIgnored" type="bool" value="true"/> should be used under rtabmap node, not rgbd_odometry node.

When RGBD/SavedLocalizationIgnored is set to false, rtabmap assumes that the robot is starting from where it stopped mapping, providing the map on start. If the initial localization is wrong (kidnapped robot problem), RTAB-Map will still relocalize the robot on loop closure / global localization. When RGBD/SavedLocalizationIgnored is set to true, rtabmap won't publish the map until it can be localized against the map saved in the database.

The problem here seems that RTAB-Map cannot accept a loop closure / global localization. Can you show warnings on terminal when a loop closure is rejected? <param name="Reg/Strategy" type="string" value="1"/> should be 0 as you don't subscribe to any laser scan inputs. Loop closures may be rejected because there are no scans used. Without a real lidar, I recommend using Reg/Strategy = 0.

I see you have "encoder odometry", make sure there is no conflict with TF sent already by rgbd_odometry. It looks like encoder_odometry and rgbd_odometry are both publishing the same TF /odom -> /base_footprint. This would likely cause strange flickering on TF as both would not give the same transform. You may want to show the tf tree too:

$ rosrun tf view_frames
$ evince frames.pdf

rgbd_odometry is independent of the map, it publishes /odom->/base_footprint. rtabmap publishes the odometry correction on /map -> /odom.

cheers,
Mathieu

edit flag offensive delete link more

Comments

Hi Mathieu

Thanks a lot for your quick response, and most of all for developing this wonderful package. It works much better now, with Reg/Strategy on 0. Detecting more loop closures and refining everything in your GUI tool offline seems to help also.

rembert gravatar image rembert  ( 2018-09-24 06:33:01 -0500 )edit

We're not publishing other odometry on the tf tree, though I tried before to fuse the encoder signals with the rgdb odometry but than the map was not correct. I might be looking further into that in the future.

rembert gravatar image rembert  ( 2018-09-24 06:35:44 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-09-07 09:22:40 -0500

Seen: 2,497 times

Last updated: Sep 07 '18