From ef8387fee6427fae54ac4f63cdb75d38add0d556 Mon Sep 17 00:00:00 2001 From: Adnan Saood Date: Tue, 12 Dec 2023 17:52:39 +0100 Subject: [PATCH] Removed unused variables in wheel ticks publisher --- .../include/irobot_create_nodes/wheels_publisher.hpp | 1 - .../irobot_create_nodes/src/wheels_publisher.cpp | 6 ------ 2 files changed, 7 deletions(-) diff --git a/irobot_create_common/irobot_create_nodes/include/irobot_create_nodes/wheels_publisher.hpp b/irobot_create_common/irobot_create_nodes/include/irobot_create_nodes/wheels_publisher.hpp index 9d9ac3de..eaf01e74 100644 --- a/irobot_create_common/irobot_create_nodes/include/irobot_create_nodes/wheels_publisher.hpp +++ b/irobot_create_common/irobot_create_nodes/include/irobot_create_nodes/wheels_publisher.hpp @@ -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_; diff --git a/irobot_create_common/irobot_create_nodes/src/wheels_publisher.cpp b/irobot_create_common/irobot_create_nodes/src/wheels_publisher.cpp index d530c8e9..702b15fc 100644 --- a/irobot_create_common/irobot_create_nodes/src/wheels_publisher.cpp +++ b/irobot_create_common/irobot_create_nodes/src/wheels_publisher.cpp @@ -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( velocity_topic, rclcpp::SystemDefaultsQoS()); RCLCPP_INFO_STREAM(get_logger(), "Advertised topic: " << velocity_topic);