Hello,
I am trying RTABmap SLAM for one of my projects. The issue I am facing here is that the environment does not have a lot of models. When I try to create a map, it creates multiple instance of same model at different locations. I am guessing, this is because it is not able to close the loop and it assumes that it is a different model altogether. Does anyone have any suggestion regarding this. I have attached the gazebo sim environment and the rviz with cloud map. Can the issue be due to the fact that it has very less number of models and there are no walls which is making it difficult for the robot to localise itself. Any kind of suggestion would be helpful.
Hi @ritwikrohan7b40210eed0d34a2d, I don’t use RTABmap much but I’d say this is not an issue with the models (although I don’t know). I think two things might also be happening:
- The odometry of your robot is not correct.
- The camera calibration is not correct.
A quick way to confirm this is to create a world with a ton of models, my guess is that the issue will still happen, and you can move on to those I suggested.
Let me know if you get it!
Hey Rodrigo,
Thanks for the reply. You were right. I tried it with same world as the course (in ignition fortress) and there is a huge odometry drift. I have used the same limo robot as used in the course but I am doing my project on gazebosim (fortress), so I had to make relevant changes like gazebo plugins etc. other than that it is using the same configurations as used the course. Do you have any suggestions to fix the odometry drift?
Hey @roalgoal
I was able to fix the issue by using a separate odometry publisher plugin. In case any one gets stuck in the future, I made these changes:
From
<gazebo>
<plugin filename="ignition-gazebo-diff-drive-system" name="ignition::gazebo::systems::DiffDrive">
<left_joint>center_left_wheel</left_joint>
<right_joint>center_right_wheel</right_joint>
<wheel_separation>0.172</wheel_separation>
<wheel_radius>0.045</wheel_radius>
<odom_publish_frequency>100</odom_publish_frequency>
<topic>cmd_vel</topic>
<odom_topic>odom</odom_topic>
<tf_topic>tf</tf_topic>
<frame_id>odom</frame_id>
<child_frame_id>base_footprint</child_frame_id>
</plugin>
</gazebo>
To this
<gazebo>
<plugin filename="ignition-gazebo-diff-drive-system" name="ignition::gazebo::systems::DiffDrive">
<left_joint>center_left_wheel</left_joint>
<right_joint>center_right_wheel</right_joint>
<wheel_separation>0.172</wheel_separation>
<wheel_radius>0.045</wheel_radius>
<odom_publish_frequency>100</odom_publish_frequency>
<topic>cmd_vel</topic>
<!-- <odom_topic>odom</odom_topic>
<tf_topic>tf</tf_topic> -->
<frame_id>odom</frame_id>
<child_frame_id>base_footprint</child_frame_id>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libignition-gazebo6-odometry-publisher-system"
name="ignition::gazebo::systems::OdometryPublisher">
<odom_frame>odom</odom_frame>
<robot_base_frame>base_footprint</robot_base_frame>
<odom_topic>odom</odom_topic>
<tf_topic>tf</tf_topic>
<dimensions>2</dimensions>
<odom_publish_frequency>10</odom_publish_frequency>
</plugin>
</gazebo>
Result:
This topic was automatically closed 5 days after the last reply. New replies are no longer allowed.