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

steering axis of carlike robot with teb_local_planner

asked 2016-06-15 03:34:55 -0600

stfn gravatar image

updated 2016-06-15 04:20:56 -0600

We have an car-like robot and use the new teb_local_planner for driving. What is missing in the documentation is the question of the steering axis (front or rear), resp. where /base_link sits on the robot. As a first step, I modified teb_local_planner_tutorials to reflect our robot model and world. In contrast to the original robot_carlike_in_stage launch example where /base_link sits on the rear axis, our /base_link frame resides in the center of the front axis (as usual for this robot model). Accordingly our (rotation) origin is at /base_link and therefore in the front and not in the back, which is also modeled in the stage parameters of the robot model.

The result of running the stage simulation is, that the car seems to steer with the back rather than the front axis. In any case, it looks wrong. Does the teb_local_planner only support car-like robots that steer with the rear axis? How do I have to model the robot to reflect steering with the front axis?

EDIT: The wheelbase parameter is described as

The distance between the drive shaft and steering axle. The value might be negative for back-wheeled robots.

So for our robot, drive shaft is in the front, as well as steering axle and /base_link. So wheelbase according to the description is 0, but the planner does not produce reasonable output with that.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
6

answered 2016-06-15 11:18:56 -0600

croesmann gravatar image

updated 2016-06-16 00:44:58 -0600

Indeed, the parameter definition for the wheelbase is misleading. The wheelbase is defined as the distance between the rear and front axle. However, the wheelbase parameter is only used in case you are sending commands to a base controller dealing with a modified Twist message such as stage in the car mode (see Section 2.2.1 here). Which one of the axles is the actual drive shaft is not relevant for the teb_local_planner, since we ignore friction, slipping etc.

Regarding your navigation setup and questions:

First of all, the planner should work with both types of car-like robots (steering with the front or rear axle). But you need to revise your model in order to make it work. The car-like robot is considered as uni-cycle model with additional constraints (limiting turning radius etc.). Thus it is important that the center of rotation is defined properly by the location of the base-link frame. You are defining the frame at the center of the steering axle, but this is not the actual center of rotation of the robot. Refer to [1] for mathematical details. Here you can also find the theory on representing a car-like robot as uni-cycle model. Section 2.2. of the car-like robot tutorial shows an example image for robots with front-steering. The base_link frame must be located at the center of the rear-axle in order to work properly with the planner (accordingly, a robot with rear-steering requires base_link to be located at the front-axle).

In summary, the following steps should be performed:

  • Front steering: locate base_link at the center of the rear-axle (rear-steering: base_link at front-axle)

  • Set the desired minimum turning radius min_turning_radius (either try it out using rqt_reconfigure or calculate the value using the relations of transforming a car-like robot to a uni-cycle model: max_steering_angle=atan(wheelbase/min_turning_radius) (-> solve w.r.t. min_turning_radius).

  • Depending on the base controller, you need to convert the twist message from the navigation stack to a message containing the linear velocity and the steering angle. Stage requires a twist message in which angular.z corresponds to the steering angle. In that case, the teb_local_planner provides an internal conversion if cmd_angle_instead_rotvel is activated. Only then, wheelbase is taken into account. The conversion is performed according to the relation mentioned above:

    steering_angle = atan(wheelbase*omega/v) if v!=0

    steering_angle = 0 if v==0

    However, sometimes it is preferable to set the steering_angle to the previous value for v=0. But in that case, you might implement your own small conversion script that subscribes to cmd_vel.


[1] [S. LaValle, Planning Algorithms, Cambridge University Press, 2006: Chapter 13](http://planning.cs.uiuc.edu/)

edit flag offensive delete link more

Comments

Thanks! Just one detail: With base_link you mean the robot_frame_id tf param (global costmap), right? So from move_base/teb_local_planner it should work (despite Stage issues) by introducing a new frame on the rear axis and setting this one as robot_frame_id. Or does it have to be base_link itself

stfn gravatar image stfn  ( 2016-06-16 06:06:59 -0600 )edit
1

Exactly, but the robot_frame_id specified for the local costmap. You should be able to introduce a new virtual frame as long as I haven't missed anything in the code ;-)

croesmann gravatar image croesmann  ( 2016-06-16 06:40:26 -0600 )edit

Question Tools

4 followers

Stats

Asked: 2016-06-15 03:34:55 -0600

Seen: 1,307 times

Last updated: Jun 16 '16