Skip to content

Commit

Permalink
Wheel Ticks calculation code equation correction (#222)
Browse files Browse the repository at this point in the history
* Fixed ticks calculation equation

* Removed unused variables in wheel ticks publisher
  • Loading branch information
adnan-saood authored Jan 13, 2024
1 parent e4ab872 commit 4ea6457
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@ class WheelsPublisher : public rclcpp::Node

// Encoder parameters
double encoder_resolution_;
double wheel_circumference_;

// Handling wheel ticks and wheel velocity messages
rclcpp::TimerBase::SharedPtr timer_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,12 +30,6 @@ WheelsPublisher::WheelsPublisher(const rclcpp::NodeOptions & options)
encoder_resolution_ =
this->declare_parameter("encoder_resolution", 508.8);

// wheel radius in meters
const double wheel_radius =
this->declare_parameter("wheel_radius", 0.03575);
// Set wheel circumference from wheel radius parameter
wheel_circumference_ = 2 * M_PI * wheel_radius;

angular_vels_publisher_ = create_publisher<irobot_create_msgs::msg::WheelVels>(
velocity_topic, rclcpp::SystemDefaultsQoS());
RCLCPP_INFO_STREAM(get_logger(), "Advertised topic: " << velocity_topic);
Expand Down Expand Up @@ -76,10 +70,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 4ea6457

Please sign in to comment.