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

How can I reduce drift in my robot's trajectory?

asked 2016-11-02 23:07:14 -0600

M@t gravatar image

updated 2016-12-12 17:04:20 -0600

The Problem (TL;DR)

My robot used to travel in straight lines between point A and point B. Now it doesn’t. I want to figure out why and how I can make it do that again by forcing the local path planner to follow the global path as closely as possible. I've done my best to summarize the problem here, but if you don't want to read an essay skip to the solution to this ROS question where I've re-stated the problem more clearly, and the work-around.


The Problem (full explanation)

If a robot travels directly between two points and there are no obstacles in the way, then its trajectory between those points should be a perfectly straight line (in theory). My robot used to behave like this, as shown below:

image description

And now it doesn't, it consistently follows a bowed/curved trajectory every time. The radius of the curve changes but otherwise the trajectory is identical. The final stretch back to the starting point also has a funny kink it. Example:

image description

Now before I go any further, I do understand that this problem is largely aesthetic and doesn't matter. And I know that I could work around this by adding more goal points and breaking the longer lines down into a series of shorter ones. However the fact remains that I can't currently explain this behaviour and I'd like to solve the problem if only for my own education.

So I would like to correct this behaviour and answer a few questions

Here is all the relevant system information:

System Information

  • OS: Ubuntu 14.04 (laptop), ROS Indigo Igloo (robot)
  • Robot: Clearpath Robotics Jackal UGV (real, not simulated)
  • Sensors: IMU, wheel encoders, high accuracy RTK GPS
  • Localization: package used is robot_localization. There are two instances of ekf_localization_node (local and global). IMU and encoder data is fused in the (local) /odom frame. IMU, encoder and GPS data is fused in the (global) /map frame - this is the frame /move_base uses for navigation. I can provide the specific launch files if requested.

    The output from the global EKF is always accurate and doesn't drift. The local output accumulates error over time and tends to drift quite badly by the end of a run.

  • Navigation: I use the jackal_navigation package (version 2.2.2) to set up my navigation stack. I use the odom_navigation_demo.launch with the following parameter changes to local_base_planner and costmap_2d:

    1. xy_goal_tolerance increased to 0.35 m
    2. heading_scoring = true (false by default)
    3. Costmap size increased to 120x120 m
    4. All instances of any "global_frame" parameter have been changed to /map.
    5. All map (local and global) "update_frequency" parameters reduced from 20 Hz to 10 Hz
    6. Reduced "controller_frequency" and "planner_frequency" parameters from 20 HZ to 10 Hz

    To the best of my knowledge, these are the only parameters that have changed between the two graphs shown above.

    The full navigation parameter files are here

    Currently, in all cases the global path is perfectly straight ...

(more)
edit retag flag offensive close merge delete

Comments

10

Even though I cannot help you here, I'd like to give a big ThumbsUp for this nice problem description. IMO, the average question lately seems to be: "My robot is not working!!! What can I do?!?!?!"

So it is nice to read such a good problem description for a change! Thank you!

mgruhler gravatar image mgruhler  ( 2016-11-03 02:29:53 -0600 )edit
1

Its hard to say what your problem is, it could be so many different things. But the behavior your seeing can be caused by a constant force that the PID controller has to deal with, (like one of the motors being bad). You could put the robot up on blocks and test that all the wheels are still driven.

shoemakerlevy9 gravatar image shoemakerlevy9  ( 2016-11-03 10:37:16 -0600 )edit
1

That's why its taking so long to debug. I've checked that all the wheels work, and they seem fine. But I think I've discovered what could be creating that constant force you mentioned - have a look at Update 1.

M@t gravatar image M@t  ( 2016-11-06 22:43:59 -0600 )edit
1

Most of the position estimators that I've worked with use the linear and angular velocity from odometry to propagate the previous position estimate to the new position estimate (and so the absolute heading from odometry is completely ignored)

ahendrix gravatar image ahendrix  ( 2016-11-09 21:24:20 -0600 )edit

So that's probably why the absolute odometry heading doesn't appear to be adversely affecting your EKF.

ahendrix gravatar image ahendrix  ( 2016-11-09 21:25:00 -0600 )edit

From the data, it looks like your robot drives slightly to the right when commanded to go straight. Maybe you need to re-tune the PID controllers now that the motors have worn in a bit?

ahendrix gravatar image ahendrix  ( 2016-11-09 21:29:11 -0600 )edit

You say is used to work and now it doesn't? Do you know what has changed between then and now?

MarkyMark2012 gravatar image MarkyMark2012  ( 2016-11-10 02:32:43 -0600 )edit

Thanks very much for your help! I've addressed your comments in "Update 3"

M@t gravatar image M@t  ( 2016-11-13 17:02:41 -0600 )edit

1 Answer

Sort by » oldest newest most voted
13

answered 2016-12-12 17:02:00 -0600

M@t gravatar image

updated 2018-01-30 19:53:49 -0600

The Solution (TL;DR)

In the parameters for the /move_base node, set: planner_frequency = 0.0

Setting heading_scoring = true in the parameters for base_local_planner also helps as it makes the robot turn corners tighter.


The Solution (full explanation)

I haven't found the real cause of the problem, I haven't figured out what changed between when I started and now. What I have done is found a work-around. I'll try to re-state the key issue and the solution as best as I can because the original question above is too big and horrible to read now.

Currently, the /move_base node has a parameter called planner_frequency, this dictates the rate at which the global planner will re-plot the global path. The ROS default is 0.0, but the default in the Clearpath files that I'm using is 20 Hz (this file specifically). With reference to this heavily exaggerated illustration, this is essentially the problem:

image description

In travelling from A to B, the robot is obviously experiencing some drift (for whatever reason), so its just not travelling straight. But when it gets off the original path (bold green), rather than getting back on it, the global path is simply re-plotted (skinny green) starting from where the robot currently is. Eventually the robot will get close enough to the goal that the local planner and controller will overrule the source of the drift. Hence the robot follows the dashed, light blue path from A to B instead of following a straight line between both points.

The simple solution is to set planner_frequency = 0.0, that way "the global planner will only run when a new goal is received or the local planner reports that its path is blocked" This means that the global path never changes between goals, so the local planner rarely deviates from it. This means that instead of this:

image description

You get this:

image description

Not perfect, but a hell of a lot better and good enough for now. In addition, the local path planner can be a little too generous with its turning arcs, so I suggest setting heading_scoring = true in the parameters for base_local_planner (assuming that is the local planner you are using of course). This forces the planner to score trajectories based on angles rather than distance, and overall gives you tighter turns.

For reference, on a Clearpath Jackal, the planner_frequency parameter is found at the following filepath: /opt/ros/indigo/share/jackal_nagivation/params/move_base_params.yaml

If I happen to stumble across the real cause of the drift, or if I figure out anything else that improves the trajectory, I'll update this again. Thanks again to everyone who helped.

edit flag offensive delete link more

Comments

I have similar sensors as your robot, I have a question. when you do the IMU and odom fusion, did your IMU has a yaw feedback ie. north or south? @M@t

jerryzhchao gravatar image jerryzhchao  ( 2016-12-16 05:19:25 -0600 )edit

Not sure what you mean sorry. My IMU reports a yaw from its magnetometer. Yaw reads 0 when facing North and increases CCW. No this doesn't adhere to REP103 but navsat_transform deals with it using the yaw_offset parameter. Everything else comes out in the wash.

M@t gravatar image M@t  ( 2016-12-19 15:04:58 -0600 )edit

Question Tools

11 followers

Stats

Asked: 2016-11-02 23:07:14 -0600

Seen: 3,378 times

Last updated: Jan 30 '18