Closed omcandido closed 7 years ago
Thanks for providing the issue report! Actually, the planner assumes base_link to be located in the center of rotation which is for a differential drive robot at the central point of the axis and for a car-like robot at the rear/front axis (front/rear steering). Generally, this definition is based on the unicycle model (e.g. see here, Chapter 13). For robots with a simple symmetric geometry the center of mass assumption might be valid and intuitive. You might create your own small converter node for your robot and add it to the pipeline between navigation stack and the base controller if the small communication overhead is ok. Otherwise we could add a parameter for switching between the two different conventions or further include pluginlib to allow the registration of multiple conversion plugins (if this flexibility is really necessary...).
Thanks a lot for your answer. There is no need for an additional plugin, I'll change base_link to the center of rotation.
Regards
I am following the tutorial to use the teb local planner with car-like robots. The function
convert_trans_rot_vel_to_steering_angle(v, omega, wheelbase)
considers that the linear velocity is taken at the center of the rear track, which is not exactly the same as at the center of mass (at the center of mass the radius is a bit greater, therefore the linear velocity must be a bit greater as well).I assume the planner gives velocity commands for the center of mass of the vehicle, so, is this conversion a deliberate approximation? If so, the exact approach would be:
radius= v/omega //at the C.M.
return wheelbase/(std::sqrt(radius*radius-wheelbase*wheelbase/4))
This last line can be proven defining
r = sqrt(radius*radius-(wheelbase/2)*(wheelbase/2)) - track/2
andsteering_angle = atan(wheelbase /(r+track/2))
.Regards