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

Understanding How Odometry Is Calculated In The Diff_Drive Controller

asked 2021-06-25 21:12:03 -0500

sameh4 gravatar image

I apologize that this question has two parts. If it's better to post two questions, then please let me know.

While reading through the source code of the diff_drive_controller.cpp, I am trying to understand how the two Odometry update methods work.

The "happy" path is the open loop update, which follows basic trigonometry, as defined by the Unicyle Kinematics. Of course this is highly susceptible to dead reckoning because of drift, tire slip, bumps, etc.

The other update seems to be much more involved, calculates a mean position, and some extra steps before applying the trigonometry.

My first question is: Where can I find more information about the model behind the more involved update?

Secondly, even with the second method of update, this odometry calculation does not use any sensors at all, not even a wheel encoder. Does this not create problems? I understand if this is by design so that there's no dependency on any specific hardware; which is a goal of this project.

But then how can I incorporate my own sensors into the control loop? How can I also add some PID to the loop as well?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2021-06-26 14:48:39 -0500

shonigmann gravatar image

I assume you are talking about Odometry::updateOpenLoop() vs. Odometry::update() (used in diff_drive_controller.cpp here and here respectively)?

If so, I don't know of any formal documentation, but I find the code reasonably clear if you follow it through. There isn't much change between the math performed in each. The big difference is the information used to perform the odometric estimate.

The Open Loop update uses the commanded linear and angular velocities and the time step to estimate where the robot moved to (assuming perfect response of the vehicle to the control input).

The "closed loop" update uses measured wheel positions to get an improved estimate of the distance the robot actually travelled. If there is more than one wheel per side (e.g. for skid steer robots), then the average position of the wheels on each side is taken to hopefully reduce noise / uncertainty / the effect of slip.

Regardless of whether open or closed loop is used, both methods use the same RungaKutta2 implementation to update the odometric estimate.

Both methods are susceptible to drift over time due to slip and other sources of uncertainty, though certainly using position feedback will result in lower drift than the fully open-loop approach.

If you want to mitigate unbounded drift over time, then you need to incorporate other local/global measurement sources. One of the most popular ways to do this in ROS/ROS2 is with the robot_localization package, which will incorporate IMU and GPS data and other odometry sources (e.g. visual odometry) to improve your robots pose estimate.

As far as modifying the control loop to add additional feedback goes, it really depends on your application. diff_drive_controller is open-loop with respect to whatever hardware interface it is interacting with. It sets the velocity that would be appropriate for the desired body twist. If under the hood you want to modify the velocity controller to behave a certain way or incorporate certain feedback, you can certainly do so. In most applications, however, your goal is to meet a target position (the intermediate velocities are often less important). If so, then I'd recommend using the navigation2 package. As long as you're publishing odometry and, localizing the robot if applicable, nav2 will perform the closed loop position control for you.

edit flag offensive delete link more

Comments

Thanks Simon! This was a very helpful answer. I previously studied this book on SLAM extensively https://github.com/gaoxiang12/slamboo..., so I have a good background. I have also wanted to checkout the nav2 package but I am taking baby steps with ROS2

sameh4 gravatar image sameh4  ( 2021-06-27 00:05:49 -0500 )edit

@shonigmann

In most applications, however, your goal is to meet a target position (the intermediate velocities are often less important). If so, then I'd recommend using the navigation2 package. As long as you're publishing odometry and, localizing the robot if applicable, nav2 will perform the closed loop position control for you.

I would be grateful if you could point out why nav2 might be preferable over nav1 (Ros 1 move_base) in this case?

Neuromorphic gravatar image Neuromorphic  ( 2021-08-17 12:17:42 -0500 )edit
2

The question was tagged with ros2 and foxy, so the answer focused on ros2/nav2 and wasn't meant to compare with nav1.

Its been a while since I've looked at nav1, but it should achieve largely the same functionality. Nav2 is a bit more modern and has received more recent attention. Nav1 may have more legacy functionality, but I think Nav2 is quickly catching up. You can find some additional details on the differences here: https://navigation.ros.org/about/ros1...

shonigmann gravatar image shonigmann  ( 2021-08-17 12:57:38 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2021-06-25 21:12:03 -0500

Seen: 1,009 times

Last updated: Jun 26 '21