ros2_controllers
ros2_controllers copied to clipboard
Odomentry not properly working with ackermann steering
Describe the bug The odometry is fine when the vehicle moves foward/backwards, but is wrong when steering. My issue seems similar to this one #933
To Reproduce This is my yaml file:
`controller_manager: ros__parameters: update_rate: 30 use_sim_time: true
ackermann_steering_controller:
type: ackermann_steering_controller/AckermannSteeringController
forks_controller:
type: position_controllers/JointGroupPositionController
joint_broad:
type: joint_state_broadcaster/JointStateBroadcaster
ackermann_steering_controller: ros__parameters: publish_rate: 50.0
rear_wheels_names: [left_wheel_joint, right_wheel_joint]
front_wheels_names: [left_steering_joint, right_steering_joint]
front_wheel_track: 0.990
rear_wheel_track: 1.042
wheelbase: 1.645
front_wheels_radius: 0.220
rear_wheels_radius: 0.285
front_steering: true
use_stamped_vel: false
max_steering_angle: 0.45
forks_controller: ros__parameters: joints: - forks_joint`
Screenshots Here is a video that shows what happens. The odometry seems fine when doing straight movements, but not when steering.
Screencast from 20-12-23 14:48:27.webm
Is there a solution?
I'm trying to reproduce your error but when I launch everything I don't have odom fixed frame in Rviz. But the odometry topic is published. Is there some param to set to enable odometry in the controller settings?
This: https://github.com/ros-controls/ros2_controllers/issues/762#issuecomment-1728236694 solved the issue of the odometry frame for me
I'm experiencing the same issues as @luj97 and the issues reported in #933. Odometry is remapped correctly but definitely wrong when steering. Could somebody tell if this is a bug in the code or else provide a working example for ackermann steering?
I've the same odometry issue with ackermann kinematics: linear motion is ok, wrong with steering.
I've (probably) found the bug. In the method:
bool SteeringOdometry::update_from_position( const double traction_right_wheel_pos, const double traction_left_wheel_pos, const double right_steer_pos, const double left_steer_pos, const double dt)
The line 139:
return update_odometry(linear_velocity, angular, dt);
Should be:
return update_odometry(linear_velocity, angular * dt , dt);
The same issue is present in the other update_from_position() methods. As I understand angular is a velocity and in the integration function it is used without the dt factor
We noticed similar issues with the outputted odometry, I believe this is the correct fix for all: https://github.com/ros-controls/ros2_controllers/pull/1118