Skip to content

Commit

Permalink
fix Ackermann steering odometry bug issue ros-controls#878
Browse files Browse the repository at this point in the history
  • Loading branch information
franzrammerstorfer committed Dec 11, 2023
1 parent fbf6290 commit 88e1c3c
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions steering_controllers_library/src/steering_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,8 +272,8 @@ std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_comma
double denominator_first_member = 2 * wheelbase_ * std::cos(alpha);
double denominator_second_member = wheel_track_ * std::sin(alpha);

double alpha_r = std::atan2(numerator, denominator_first_member - denominator_second_member);
double alpha_l = std::atan2(numerator, denominator_first_member + denominator_second_member);
double alpha_r = std::atan2(numerator, denominator_first_member + denominator_second_member);
double alpha_l = std::atan2(numerator, denominator_first_member - denominator_second_member);
steering_commands = {alpha_r, alpha_l};
}
return std::make_tuple(traction_commands, steering_commands);
Expand Down

0 comments on commit 88e1c3c

Please sign in to comment.