ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | Q&A answers.ros.org |
![]() | 1 | initial version |
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