introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
922 stars 549 forks source link

Making a map with reference points #1062

Closed coen132 closed 7 months ago

coen132 commented 7 months ago

Hey,

I'm trying to make a map with RTABmap of a warehouse where I have RFID tags in the floor. I want to use the RFID tags as ground truth, already have a function which sets the pose of my robot as soon as I drive over the first two tags. The problem is that rtabmap always starts mapping from origin 0,0,0, does anybody know what the most simple way is to set the initial position for mapping?

Thanks in advance!

matlabbe commented 7 months ago

rtabmap first node is not always (0,0), but would match the odometry pose received, which is often (0,0) when the mapping is started and the robot didn't move yet.

If you set Optimizer/PriorsIgnored to false, you may be able to use /rtabmap/global_pose topic to publish a global pose to rtabmap when a RFID is detected. If you know the global position of that tag and the relative position of the robot to that tag when detected, publishing /rtabmap/global_pose (geometry_msgs/PoseWithCovarianceStamped) with the robot pose in that coordinate frame and some covariance (depending how accurate the RFID detection is). On 2D case, you would have to fill only x,y and yaw parameters of the covariance matrix:

x 0 0    0    0    0
0 y 0    0    0    0
0 0 9999 0    0    0
0 0 0    9999 0    0 
0 0 0    0    9999 0
0 0 0    0    0    yaw

If you cannot know the yaw orientation relative to tag, set yaw to 9999:

x 0 0    0    0    0
0 y 0    0    0    0
0 0 9999 0    0    0
0 0 0    9999 0    0 
0 0 0    0    9999 0
0 0 0    0    0    9999

cheers, Mathieu