ROSBot 3: Problems with AMCL

Hello,
When using AMCL for the navigation of the robot, the estimated orientation of the pose tends to be really inaccurate. This causes for the map to continually rotate, sometime as much as face the completely opposite direction between updates. I have tried changing the values of the alphas in the configuration to reflect that the orientation of the robot from the odometry is not reliable, due to the slippage of the wheels while turning. However this has yielded no improvement. How should I modify the configuration to improve the localisation?

Thank you very much,
David.

Hello @DavRodFer,

As of today, we have not yet migrated the logic from rosbot-autonomy to the jazzy distribution. However, you can be inspired by this repository, as the differences between humble and jazzy versions are not very big.

First of all, when playing with navigation and localization, you should make sure that the odom and sensor data return sensible data.

Another common source of errors is incorrectly set transformations

  • in urdf relative to the physical robot
  • in the node config.

Hello @RafalGorecki,
Thanks for the quick response. When checking the odometry of the robot I notice a significant drift when moving forwards and backwards. On the other hand, the estimate of the orientation of the robot seems to be quite precise, contrary to what I first thought. How can I improve the odometry?

As you have said the there are minimal differences between the AMCL configuration between the humble and jazzy ROS2 versions, in fact the configuration I have been using is identical to the one in rosbot-autonomy.

amcl:
  ros__parameters:  
    use_sim_time: False

    global_frame_id: "map"
    odom_frame_id: "odom"
    base_frame_id: "base_link" # Robot base frame.
    scan_topic: scan
    map_topic: map

    robot_model_type: "nav2_amcl::DifferentialMotionModel"

    set_initial_pose: true
    always_reset_initial_pose: true

    tf_broadcast: true
    transform_tolerance: 1.0

    alpha1: 0.2 # Expected process noise in odometry’s rotation estimate from rotation.
    alpha2: 0.2 # Expected process noise in odometry’s rotation estimate from translation.
    alpha3: 0.2 # Expected process noise in odometry’s translation estimate from translation.
    alpha4: 0.2 # Expected process noise in odometry’s translation estimate from rotation.
    alpha5: 0.2 # For Omni models only: translation noise.

    do_beamskip: false
    beam_skip_distance: 0.5 # Ignore beams that most particles disagree with in Likelihood field model. Maximum distance to consider skipping for (m).
    beam_skip_error_threshold: 0.9
    beam_skip_threshold: 0.3

    lambda_short: 0.1
    laser_likelihood_max_dist: 2.0
    laser_max_range: 12.0
    laser_min_range: 0.2
    laser_model_type: "likelihood_field"
    max_beams: 60
    max_particles: 500
    min_particles: 200

    pf_err: 0.05
    pf_z: 0.99

    recovery_alpha_fast: 0.0
    recovery_alpha_slow: 0.0
    
    resample_interval: 1
    save_pose_rate: 0.5
    sigma_hit: 0.2

    first_map_only: false

    update_min_a: 0.3
    update_min_d: 0.2

    z_hit: 0.5
    z_max: 0.05
    z_rand: 0.5
    z_short: 0.05

    initial_pose:
      x: 0.0
      y: 0.0
      z: 0.0
      yaw: 0.0

Lastly, if I understand correctly, the AMCL node should create a transformation from “map” to “odom”, as configured in the YAML file. Additionally, the urdf is provided and is correct.

I am still unsure what could be the cause for that drift in the odometry. What do you think it could be?

Thanks for the help,
David.

Hello

Regarding odometry, I wonder if there might be a magnetic field in the room you are in that could affect the readings from the IMU magnetometer.
If so, the IMU data could be falsified, which would cause orientation problems.
You can see the raw data from the topic /imu_broadcaster/imu. If the orientation changes significantly when moving forward/backward, this suggests the presence of magnetic fields.
There may be a drift from the gyroscope, but it should not be greater than 0.005 (angular_velocity).

Regarding the operation of AMCL. AMCL creates a map->odom transformation, but unlike SLAM it does not create a map. The map must be provided before the algorithm is initialized.

Regards

I have another suggestion which by the way may help with your second issue.

If you need navigation and AMCL you can use the rosbot-autonomy demo. It is written for ROS Humble for now. But maybe it seems to me that it provides the functionality you are looking for. If it turns out that the problem occurs only on jazzy it will be an indication that the problem is related to the last software migration.

Hello @RafalGorecki,

Regarding the odometry, the problem does not lay in the orientation of the odometry as initially stated in the post. There exists a significant drift in the linear estimation of the displacement. I have been able to notice this by fixing the transformation from the “map” frame to the “odom” frame and locating the robot so it aligns with that position, using the reading of the LiDAR. After doing this I moved the robot around manually and there was a significant drift from the LiDAR reading to the map, which initially lined up. This drift does not occur when just rotating in place.

Regarding the operation of AMCL, I am informed about what you are indicating.

Regarding using the ROS Humble version of rosbot-autonomy, I am not really sure how this would solve the problem with the odometry.

Thank you very much,
David.

Hello,
I have been running some tests on the odometry and the estimated displacement of the robot using just the odometry is around 2.12 times the real one. How could I solve this?

Regards,
David.

What exactly do you mean, where did the value 2.12 come from?

Could you reset the driver, then drive a distance of 3 meter forward, and let me know what the value of displacement x is for the topics odometry/filtered and rosbot_base_controller/odom?

Hello,
Yesterday I did what you are saying and that is where the value came from. I used the value from odometry/filtered that it is what I use for the localisation. Until next week I will not have access again to the robot. I will check then with the other topic you mention.

Regard,
David.