Skip to content

Commit

Permalink
remove const tag from some of the callback methods
Browse files Browse the repository at this point in the history
Signed-off-by: Aleksander Szymański <[email protected]>
  • Loading branch information
Bitterisland6 committed Dec 20, 2023
1 parent 05cd60a commit 8611dd4
Showing 1 changed file with 9 additions and 9 deletions.
18 changes: 9 additions & 9 deletions leo_fw/src/firmware_message_converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class FirmwareMessageConverter : public rclcpp::Node
joint_states_pub_->publish(joint_states);
}

void wheel_odom_callback(const leo_msgs::msg::WheelOdom::SharedPtr msg) const
void wheel_odom_callback(const leo_msgs::msg::WheelOdom::SharedPtr msg)
{
nav_msgs::msg::Odometry wheel_odom;
wheel_odom.header.frame_id = odom_frame_id_;
Expand All @@ -126,7 +126,7 @@ class FirmwareMessageConverter : public rclcpp::Node
wheel_odom_pub_->publish(wheel_odom);
}

void mecanum_odom_callback(const leo_msgs::msg::WheelOdomMecanum::SharedPtr msg) const
void mecanum_odom_callback(const leo_msgs::msg::WheelOdomMecanum::SharedPtr msg)
{
nav_msgs::msg::Odometry wheel_odom;
wheel_odom.header.frame_id = odom_frame_id_;
Expand All @@ -151,7 +151,7 @@ class FirmwareMessageConverter : public rclcpp::Node
wheel_odom_mecanum_pub_->publish(wheel_odom);
}

void imu_callback(const leo_msgs::msg::Imu::SharedPtr msg) const
void imu_callback(const leo_msgs::msg::Imu::SharedPtr msg)
{
sensor_msgs::msg::Imu imu;
imu.header.frame_id = tf_frame_prefix_ + imu_frame_id_;
Expand All @@ -175,7 +175,7 @@ class FirmwareMessageConverter : public rclcpp::Node
imu_pub_->publish(imu);
}

void merged_odometry_callback() const
void merged_odometry_callback()
{
nav_msgs::msg::Odometry merged_odom;
merged_odom.header.frame_id = odom_frame_id_;
Expand Down Expand Up @@ -415,11 +415,11 @@ class FirmwareMessageConverter : public rclcpp::Node

// Merged Odom variables
static constexpr double PI = 3.141592653;
mutable double velocity_linear_x;
mutable double velocity_linear_y;
mutable double velocity_angular_z;
mutable double odom_merged_yaw;
mutable geometry_msgs::msg::Point odom_merged_position;
double velocity_linear_x;
double velocity_linear_y;
double velocity_angular_z;
double odom_merged_yaw;
geometry_msgs::msg::Point odom_merged_position;

// Parameters
std::string robot_frame_id_ = "base_link";
Expand Down

0 comments on commit 8611dd4

Please sign in to comment.