ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
13

Bad maps produced by gmapping in simulation with feature-poor environments

asked 2014-08-06 09:01:00 -0600

zsaigol gravatar image

I've found that in relatively feature-poor environments, e.g. a large rectangular room, the maps produced by gmapping can be very wrong. This is using a Turtlebot simulated in Gazebo, I'm not sure how transferrable this issue is. Also when using the environment from the tutorial gmapping works fine, so I suspect it's the lack of features causing the problem.

The symptoms are that the robots position jumps suddenly by up to ~1.5m, and walls it maps from then on are offset correspondingly.

I've tracked down the cause of this to "scan matching" in the OpenSLAM Gmapping code - particle locations are updated in two cases, first when applying the motion model, and second when each particle is 'jiggled' by the scan matcher to better fit the scan data. The fix for this is to change the minimumScore gmapping parameter to a large value:

<param name="minimumScore" value="10000"/>

by editing / copying gmapping.launch.xml. This turns gmapping into a pure mapping rather than a SLAM algorithm. However, the odometry provided by Gazebo seems pretty good, and not the cause of the problem (as some people seem to have suspected previously, e.g. http://answers.ros.org/question/12919/map-and-odom-after-mapping-the-environment/).

You can also set the motion model noise to zero, and reduce the number of particles to 1:

<param name="srr" value="0.0"/>
<param name="srt" value="0.0"/>
<param name="str" value="0.0"/>
<param name="stt" value="0.0"/>
<param name="particles" value="1"/>

which means the algorithm assumes the odometry is perfect. I think there might be some benefit in leaving these parameters as the default, to allow some corrections as the Gazebo odometry drifts, but I'm not completely sure.

edit retag flag offensive close merge delete

Comments

This is the first time I hear about the minimumScore parameter. I have added to the gmapping documentation. It can be a very interesting tweak for some people reporting robot "jumps" while mapping, specially because the default values is 0!.

jorge gravatar image jorge  ( 2014-08-06 10:21:10 -0600 )edit

If Odometry is perfect, no need scanmatching. Scan matching is to correct pose of the robot. Reasons for fail may be your robot is moving with hight veloctiy. Try by increasing number of particle. Please share map you build so far.

bvbdort gravatar image bvbdort  ( 2014-08-06 10:33:39 -0600 )edit

@jorge - I mostly just meant this post to help people out. Regarding the motion model noise, the first question (which I don't need answering) is: 1) Why doesn't Gazebo produce perfect odometry? - I can see that it makes sense most of the time to simulate the real robot as faithfully as possible.

zsaigol gravatar image zsaigol  ( 2014-08-06 10:50:42 -0600 )edit

@jorge - the second question I'm not 100% sure of is: 2) Does keeping noise non-zero in the gmapping parameters mean we get a more accurate localisation even when the scan-matcher is effectively disabled? Yes, i.e. gmapping still chooses the best particle.

zsaigol gravatar image zsaigol  ( 2014-08-06 10:52:12 -0600 )edit

@bvbdort - I'm happy that disabling the scan matching fixes the problem, thanks anyway.

zsaigol gravatar image zsaigol  ( 2014-08-06 10:53:44 -0600 )edit

@zsaigol hello, could you tell me how to disable the scan matching? thanks in advance

drtritm gravatar image drtritm  ( 2020-05-26 13:41:29 -0600 )edit

Thanks for the information. Please, can you suggest for me how to select the correct Gmapping odometry model noise (srr, srt, str, stt) ? Is it correct to calculate the RMSE between /cmd_vel/linear/x and /odom/twist/twsit/linear/x for translation and RMSE between /cmd_vel/angular/z and /odom/twist/twist/angular/z for rotation ?

Zuhair95 gravatar image Zuhair95  ( 2022-08-15 06:57:22 -0600 )edit

3 Answers

Sort by ยป oldest newest most voted
6

answered 2014-08-06 10:23:34 -0600

jorge gravatar image

updated 2014-08-06 12:40:24 -0600

Ah, ok. Yes, it's an interesting information what you are providing here. I will try to contribute with this answerm as my previous comment was not very precise, admittedly. There're two different things here:

  • Gmapping odometry model noise (srr, srt, str, stt) reflects the confidence the slam algorithm can have on odometry readings, and so cannot be zero unless the odometry is perfect, what only can happen on simulation. I supposed that, when gmapping corrects current pose based on scan matching, it should have some kind of "inertia" to keep in the same position, the bigger the more accurate is the odometry, and don't move at all if the odometry is perfect. But I noticed that that's not the case, that even with zero srr, srt, str and stt the robot can jump, and thanks to your question I see now that the reason can be that minimumScore parameter is 0, by default.
  • Simulated (Gazebo) odometry model noise should not be zero, (except, maybe, for particular experiments) so the simulated robots mimics faithfully enough the robot, with their inaccuracies, so it can serves as test-bench for your algorithms. But as explained in this issue, Kobuki (and so TB2) is perfect on Gazebo, what should be fixed.

mmm... I pretended to write only some lines! ^_^ Sorry for been so verbose.

UPDATE I have tried gmapping demo on gazebo by setting minimumScore to 100 and works notably better, eliminating jumps when there aren't obstacles in the fov; thanks zsaigol!

edit flag offensive delete link more

Comments

Thank you for this fruitful information. I have also noticed turtlebot was jumping really often when I SLAM.. Will you make a PR to turtlebot_navigation?

jihoonl gravatar image jihoonl  ( 2014-08-06 19:13:35 -0600 )edit

Thanks for this clarification, jorge. I had thought the TB2 odometry drifted a bit, as I tried comparing 'tf_echo /odom /base_footprint' to the 'mobile_base' pose from topic /gazebo/model_states, but the discrepancy is tiny and may not really be increasing (2 cm after 10 mins).

zsaigol gravatar image zsaigol  ( 2014-08-07 05:59:44 -0600 )edit

Hi Jorge, we faced an interesting case with gmapping/kobuki. we produce good maps but robot pose keeps teleporting 20-25cm every now & then. we tried everything & it didnt help. Turned off built-in IMU_heading & pose jumps got significantly smaller. ever faced similar problem? firmware is 1.1.4.

stevej_80 gravatar image stevej_80  ( 2016-03-06 00:52:09 -0600 )edit

@zsaigol But what if you want to keep minimumScore to a high value at some point and low at some other point. For example a very long corridor with a turning. In the long corridor, a high minimunScore could be used while at turning a low value. Is it possible to do this switching during the on-going simulation?

tsdk00 gravatar image tsdk00  ( 2019-07-30 09:57:01 -0600 )edit

Thanks for the information. Please, can you suggest for me how to select the correct Gmapping odometry model noise (srr, srt, str, stt) ? Is it correct to calculate the RMSE between /cmd_vel/linear/x and /odom/twist/twsit/linear/x for translation and RMSE between /cmd_vel/angular/z and /odom/twist/twist/angular/z for rotation ?

Zuhair95 gravatar image Zuhair95  ( 2022-08-15 06:56:53 -0600 )edit
3

answered 2019-05-26 14:22:48 -0600

xj yang gravatar image

For people only want to rely on original odometry data as the tf input (which means gmapping does no localization), set transform_publish_period to 0 may help

edit flag offensive delete link more

Comments

it worked, thanks

drtritm gravatar image drtritm  ( 2020-05-26 14:14:10 -0600 )edit

Thanks for the information. Please, can you suggest for me how to select the correct Gmapping odometry model noise (srr, srt, str, stt) ? Is it correct to calculate the RMSE between /cmd_vel/linear/x and /odom/twist/twsit/linear/x for translation and RMSE between /cmd_vel/angular/z and /odom/twist/twist/angular/z for rotation ?

Zuhair95 gravatar image Zuhair95  ( 2022-08-15 06:57:04 -0600 )edit
2

answered 2014-08-07 12:28:06 -0600

zsaigol gravatar image

updated 2014-08-07 12:28:45 -0600

To help anyone else trying to debug this, I thought I'd post my node that prints out the robot's pose from 3 sources:

  1. The Gazebo model which I think is the ground truth, via topic /gazebo/model_states
  2. The odometry published by Gazebo
  3. The robot pose published by gmapping

While there may not be any noise added to Gazebo's odometry, it isn't simply publishing the ground truth, as you can see if you drive the robot into a wall for a bit.

#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Pose.h>
#include <gazebo_msgs/ModelStates.h>

tf::TransformListener * listener;
bool received_gazebo_message = false;
geometry_msgs::Pose model_pose;

void receivedGazeboMessage(const gazebo_msgs::ModelStatesPtr& model_states)
{
    if (!received_gazebo_message)
    {
        std::cout << "Gazebo model info received!" << std::endl;
    }
    for (unsigned int i = 0; i < model_states->name.size(); ++i)
    {
        if (model_states->name[i] == "mobile_base")
        {
            model_pose = model_states->pose[i];
            received_gazebo_message = true;
            break;
        }
    }
}

void printPoses(const ros::TimerEvent&)
{
    if (received_gazebo_message)
    {
        tf::StampedTransform odom_transform;
        tf::StampedTransform gmap_transform;
        try
        {
            listener->lookupTransform("/odom", "/base_footprint", ros::Time(0), odom_transform);
            listener->lookupTransform("/map", "/base_footprint", ros::Time(0), gmap_transform);
        }
        catch (tf::TransformException & ex)
        {
            ROS_ERROR("%s", ex.what());
            return;
        }
        std::cout << std::setiosflags(std::ios::fixed) << std::setprecision(3);
        std::cout << "* at " << odom_transform.stamp_.toSec() << ":" << std::endl;

        std::cout << "Model: " << model_pose.position.x << ", " << model_pose.position.y <<
                " / " << tf::getYaw(model_pose.orientation) << std::endl;
        std::cout << "Odom : " << odom_transform.getOrigin()[0] << ", " <<
                odom_transform.getOrigin()[1] <<
                " / " << tf::getYaw(odom_transform.getRotation()) << std::endl;
        std::cout << "Gmapg: " << gmap_transform.getOrigin()[0] << ", " <<
                gmap_transform.getOrigin()[1] <<
                " / " << tf::getYaw(gmap_transform.getRotation()) << std::endl;
    }
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "pose_printer");
    ros::NodeHandle n;
    listener = new tf::TransformListener();

    ros::Subscriber gazebo_ground_truth_sub =
                n.subscribe("/gazebo/model_states", 1, &receivedGazeboMessage);
    ros::Timer timer1 = n.createTimer(ros::Duration(1.0), printPoses);

    ros::spin();
    return 0;
}
edit flag offensive delete link more

Comments

@zsaigol It's not entirely clear to me how this node is supposed to be used. Could you please explain?

gleb gravatar image gleb  ( 2016-09-06 09:16:37 -0600 )edit

Hi @gleb, the node doesn't really do anything - it just prints out the pose of the robot, as calculated in 3 different ways (as described above). You just run up Gazebo with the simulated Turtlebot, start this node, and it should print stuff out. Haven't tested with newer ROS versions, though.

zsaigol gravatar image zsaigol  ( 2016-09-07 02:42:52 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2014-08-06 09:01:00 -0600

Seen: 7,010 times

Last updated: May 26 '19