Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Odomentry not properly working with ackermann steering #937

Closed
luj97 opened this issue Dec 20, 2023 · 5 comments · Fixed by #1150
Closed

Odomentry not properly working with ackermann steering #937

luj97 opened this issue Dec 20, 2023 · 5 comments · Fixed by #1150
Labels

Comments

@luj97
Copy link

luj97 commented Dec 20, 2023

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?

@luj97 luj97 added the bug label Dec 20, 2023
@kartman88
Copy link

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?

@luj97
Copy link
Author

luj97 commented Jan 3, 2024

This: #762 (comment) solved the issue of the odometry frame for me

@ninoweg
Copy link

ninoweg commented Feb 13, 2024

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?

@messageid
Copy link

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

@MCFurry
Copy link
Contributor

MCFurry commented May 6, 2024

We noticed similar issues with the outputted odometry, I believe this is the correct fix for all:
#1118

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging a pull request may close this issue.

5 participants