Skip to content

Commit

Permalink
Fixed ticks calculation equation
Browse files Browse the repository at this point in the history
  • Loading branch information
adnan-saood committed Dec 12, 2023
1 parent fa3d501 commit 025d10d
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,10 @@ void WheelsPublisher::publisher_callback()

// Calculate and write WheelTicks msg
const double left_ticks =
(get_dynamic_state_value("left_wheel_joint", "position") / wheel_circumference_) *
(get_dynamic_state_value("left_wheel_joint", "position") / (2 * M_PI)) *
encoder_resolution_;
const double right_ticks =
(get_dynamic_state_value("right_wheel_joint", "position") / wheel_circumference_) *
(get_dynamic_state_value("right_wheel_joint", "position") / (2 * M_PI)) *
encoder_resolution_;

wheel_ticks_msg_.ticks_left = std::round(left_ticks);
Expand Down

0 comments on commit 025d10d

Please sign in to comment.