diffbot
diffbot copied to clipboard
Laser scan translation wrong when robot turn
https://user-images.githubusercontent.com/48290085/145632117-82781293-bd34-4f18-8462-d6b6662ad1a6.mp4
Hi guys, I'm facing an issue that when I turn robot around in SLAM mode the laser scan effect was displaying wrong pose/translation, specially, its gonna fit the environment only when robot stop moving (showing in video). I'm thinking about that I got wrong odometry calculation or maybe the laser frequency update was not fast enough. This issue effected to navigation process that robot would turn into recovery mode. I didn't find the answer yet so I hope you guys could help me out. Actually, I tried to fix this by using all same configurations with the Turtlebot3 robot but I haven't solve it yet because this issue didn't happen to this robot :// Many thanks in advanced!
Regards, rabbit.
Hi @funnyrabbitvu, thanks for reporting this problem! I am also aware of this issue and like you mention this happens most likely because the odometry is not accurate enough. In simulation (and real world) there are a lot of settings to tweak in order to improve this issue. For the new robot Remo, found in the remo_description
package (which is different to the "old diffbot_description
"), I invested a lot of time to tune some of the following parameters. One of the important ones were to set the wheel base (distance between wheels) and wheel radius correctly. Otherwise the odometry calculations are obviously wrong and lead to the problem you are showing.
- wheel base and radius in
diffbot_control/config
https://github.com/ros-mobile-robots/diffbot/blob/327f39559a7d7f2a49ea5a9534b941f7777e483b/diffbot_control/config/diffbot_control.yaml#L30-L34
- Use correct mass values for the components of your robot (here I tried to do this for Remo). The mass values in
diffbot_description/config
are probably not entirely correct yet. - Tune the simulated joint/wheel friction in the robot description (see the changes made here for example). For
diffbot_description
this hasn't been done yet. - Change gazebo settings of the simulated world. For comparision here is turtlebots world settings (which should be the same).
- Adapt amcl parameters to compensate for bad odometry using vision sensors (2D laser in our case). Here,
odom_model_type=diff-corrected
,odom_alphaX
andupdate_min_a
improved the behavior (you can see the commit here where I tried tuning these values).
Adapting these parameters improved the behavior but it is still not perfect as you can see in the following video of Remo twisting around:
https://user-images.githubusercontent.com/1286618/145669976-2c20a232-7f12-42be-b426-dc362efa2042.mp4
Now the thing is, that currently most values are tuned for Remo robot and not the "old diffbot model" (found in the diffbot_description
), which you are using. To alleviate this issue for both models, we should tune both models as good as possible, e.g. the gazebo related settings in the diffbot/remo_description
(for diffbot this hasn't been extensivly done yet) and also use a specific parameter set, depending on which robot is used by the user.
What I also noticed is that in Gazebo simulator the scans are not matching to the obstacles either:
https://user-images.githubusercontent.com/1286618/145671681-5315b8c5-2981-48a5-b46a-749b5d9c5d54.mp4
However, this might be not an issue as it also happens with turtlebot3:
https://user-images.githubusercontent.com/1286618/145672320-fae66885-3d0d-4296-a356-2b82e1b472a2.mp4
Regarding why for turtlebot3 the scans are aligned more accurately with the map, I have only some assumptions, which I want to list here:
- Turtlebot3 uses the
libgazebo_ros_diff_drive
gazebo plugin (here for burger). Instead of that, diffbot and Remo use thegazebo_ros_control
plugin in combination with thediff_drive_controller
. - Turtlebot3 uses an imu. A (simulated) imu together with encoder odometry fused together by an EKF might improve the odometry (after tuning everything correctly). Here the official gazebo imu plugins might help or the ones from hector group together with the robot_localization EKF. A robot that is also worth looking at is mir_robot or husky, both use
libhector_gazebo_ros_imu
. The difference between theGazeboRosImuSensor
is explained here. - ... there might be other reasons why the scans align more precisely for turtlebot3 compared to Remo
Other settings I looked at but didn't seem to have a big impact are:
- Setting PID values for gazebo in the
diffbot_control/config
(related links are found here and here. I haven't tested yet setting PID gains for uncontrolled joints indiffbot_control/config
(I don't think it helps though) -
pose/twist_covariance_diagonal
indiffbot_control/config
As it might help, I will also add some of the answers/sources I found regarding this issue and the parameters that influence it:
-
http://gazebosim.org/tutorials?tut=friction
-
https://answers.ros.org/question/30539/choosing-the-right-coefficients-for-gazebo-simulation/
-
http://sdformat.org/spec?ver=1.5&elem=collision#ode_mu
-
https://robotics.stackexchange.com/questions/15265/ros-gazebo-odometry-issue
-
https://answers.ros.org/question/345727/adding-friction-to-model-wheels/
-
https://answers.ros.org/question/231880/how-to-improve-amcl-pose-estimate/
-
https://answers.ros.org/question/237453/how-can-i-help-amcl-deal-with-catastrophic-wheel-slips/
-
https://answers.ros.org/question/9480/is-there-a-good-way-to-verify-my-odometry-data-is-sensible/#808
-
https://answers.ros.org/question/253848/laser-scan-data-not-aligned-with-map-data-and-real-world-navigation-stack/
-
https://answers.ros.org/question/345727/adding-friction-to-model-wheels/
-
https://answers.ros.org/question/156931/amcl-and-odometry-covariance-all-zeros-ok/
-
https://answers.ros.org/question/300999/confused-with-amcl-map-to-odom-transform/
-
https://answers.ros.org/question/192010/amcl-publish-frequency-map-odom/
-
https://answers.ros.org/question/363055/ros-amcl-package-interpretation-of-the-abbreviation-amcl/
-
https://answers.ros.org/question/269280/how-to-make-better-maps-using-gmapping/
-
https://answers.ros.org/question/258420/ball-joint-in-urdf/
-
https://answers.ros.org/question/307520/what-are-the-steps-to-use-diff_drive_controller-in-a-physical-robot/
Finally, I want to highlight that I would love to see a good/clear solution to this issue, so any other findings you have about this are most welcome. I hope find time soon to add an IMU to the robot and also test it extensively in simulation. So far I just did a quick test with a simulated imu but without a lot of parameter tuning (imu and ekf).
Hi @funnyrabbitvu, thanks for reporting this problem! I am also aware of this issue and like you mention this happens most likely because the odometry is not accurate enough. In simulation (and real world) there are a lot of settings to tweak in order to improve this issue. For the new robot Remo, found in the
remo_description
package (which is different to the "olddiffbot_description
"), I invested a lot of time to tune some of the following parameters. One of the important ones were to set the wheel base (distance between wheels) and wheel radius correctly. Otherwise the odometry calculations are obviously wrong and lead to the problem you are showing.
- wheel base and radius in
diffbot_control/config
https://github.com/ros-mobile-robots/diffbot/blob/327f39559a7d7f2a49ea5a9534b941f7777e483b/diffbot_control/config/diffbot_control.yaml#L30-L34
- Use correct mass values for the components of your robot (here I tried to do this for Remo). The mass values in
diffbot_description/config
are probably not entirely correct yet.- Tune the simulated joint/wheel friction in the robot description (see the changes made here for example). For
diffbot_description
this hasn't been done yet.- Change gazebo settings of the simulated world. For comparision here is turtlebots world settings (which should be the same).
- Adapt amcl parameters to compensate for bad odometry using vision sensors (2D laser in our case). Here,
odom_model_type=diff-corrected
,odom_alphaX
andupdate_min_a
improved the behavior (you can see the commit here where I tried tuning these values).Adapting these parameters improved the behavior but it is still not perfect as you can see in the following video of Remo twisting around:
remo_twist_issue_wheel_base.mp4 Now the thing is, that currently most values are tuned for Remo robot and not the "old diffbot model" (found in the
diffbot_description
), which you are using. To alleviate this issue for both models, we should tune both models as good as possible, e.g. the gazebo related settings in thediffbot/remo_description
(for diffbot this hasn't been extensivly done yet) and also use a specific parameter set, depending on which robot is used by the user.What I also noticed is that in Gazebo simulator the scans are not matching to the obstacles either:
remo_twist_issue_gazebo.mp4 However, this might be not an issue as it also happens with turtlebot3:
turtlebot3_gazebo_twist_issue.mp4 Regarding why for turtlebot3 the scans are aligned more accurately with the map, I have only some assumptions, which I want to list here:
- Turtlebot3 uses the
libgazebo_ros_diff_drive
gazebo plugin (here for burger). Instead of that, diffbot and Remo use thegazebo_ros_control
plugin in combination with thediff_drive_controller
.- Turtlebot3 uses an imu. A (simulated) imu together with encoder odometry fused together by an EKF might improve the odometry (after tuning everything correctly). Here the official gazebo imu plugins might help or the ones from hector group together with the robot_localization EKF. A robot that is also worth looking at is mir_robot or husky, both use
libhector_gazebo_ros_imu
. The difference between theGazeboRosImuSensor
is explained here.- ... there might be other reasons why the scans align more precisely for turtlebot3 compared to Remo
Other settings I looked at but didn't seem to have a big impact are:
- Setting PID values for gazebo in the
diffbot_control/config
(related links are found here and here. I haven't tested yet setting PID gains for uncontrolled joints indiffbot_control/config
(I don't think it helps though)pose/twist_covariance_diagonal
indiffbot_control/config
As it might help, I will also add some of the answers/sources I found regarding this issue and the parameters that influence it:
- http://gazebosim.org/tutorials?tut=friction
- https://answers.ros.org/question/30539/choosing-the-right-coefficients-for-gazebo-simulation/
- http://sdformat.org/spec?ver=1.5&elem=collision#ode_mu
- https://robotics.stackexchange.com/questions/15265/ros-gazebo-odometry-issue
- https://answers.ros.org/question/345727/adding-friction-to-model-wheels/
- https://answers.ros.org/question/231880/how-to-improve-amcl-pose-estimate/
- https://answers.ros.org/question/237453/how-can-i-help-amcl-deal-with-catastrophic-wheel-slips/
- https://answers.ros.org/question/9480/is-there-a-good-way-to-verify-my-odometry-data-is-sensible/#808
- https://answers.ros.org/question/253848/laser-scan-data-not-aligned-with-map-data-and-real-world-navigation-stack/
- https://answers.ros.org/question/345727/adding-friction-to-model-wheels/
- https://answers.ros.org/question/156931/amcl-and-odometry-covariance-all-zeros-ok/
- https://answers.ros.org/question/300999/confused-with-amcl-map-to-odom-transform/
- https://answers.ros.org/question/192010/amcl-publish-frequency-map-odom/
- https://answers.ros.org/question/363055/ros-amcl-package-interpretation-of-the-abbreviation-amcl/
- https://answers.ros.org/question/269280/how-to-make-better-maps-using-gmapping/
- https://answers.ros.org/question/258420/ball-joint-in-urdf/
- https://answers.ros.org/question/307520/what-are-the-steps-to-use-diff_drive_controller-in-a-physical-robot/
Finally, I want to highlight that I would love to see a good/clear solution to this issue, so any other findings you have about this are most welcome. I hope find time soon to add an IMU to the robot and also test it extensively in simulation. So far I just did a quick test with a simulated imu but without a lot of parameter tuning (imu and ekf).
Many thanks for your awesome support, bro. I'm trying to figure it out with your guideline. I will report my working status.