diff --git a/steering_controllers_library/src/steering_odometry.cpp b/steering_controllers_library/src/steering_odometry.cpp index aadd047f2e..6f58927bf9 100644 --- a/steering_controllers_library/src/steering_odometry.cpp +++ b/steering_controllers_library/src/steering_odometry.cpp @@ -169,7 +169,7 @@ bool SteeringOdometry::update_from_velocity( steer_pos_ = (right_steer_pos + left_steer_pos) * 0.5; double linear_velocity = (right_traction_wheel_vel + left_traction_wheel_vel) * wheel_radius_ * 0.5; - const double angular = steer_pos_ * linear_velocity / wheelbase_; + const double angular = tan(steer_pos_) * linear_velocity / wheelbase_; return update_odometry(linear_velocity, angular, dt); }