diff --git a/src/modelec_com/include/modelec_com/pcb_odo_interface.hpp b/src/modelec_com/include/modelec_com/pcb_odo_interface.hpp index 2622810..f5a5b09 100644 --- a/src/modelec_com/include/modelec_com/pcb_odo_interface.hpp +++ b/src/modelec_com/include/modelec_com/pcb_odo_interface.hpp @@ -56,7 +56,7 @@ namespace Modelec rclcpp::Subscription::SharedPtr odo_add_waypoints_subscriber_; rclcpp::Subscription::SharedPtr odo_set_pos_subscriber_; rclcpp::Subscription::SharedPtr odo_set_pid_subscriber_; - rclcpp::Subscription::SharedPtr cmd_vel_subscriber_; + rclcpp::Subscription::SharedPtr joy_subscriber_; void AddWaypointCallback(const modelec_interfaces::msg::OdometryWaypoint::SharedPtr msg); void AddWaypointsCallback(const modelec_interfaces::msg::OdometryWaypoints::SharedPtr msg); diff --git a/src/modelec_com/src/pcb_odo_interface.cpp b/src/modelec_com/src/pcb_odo_interface.cpp index 50a9e3b..bc5ed8c 100644 --- a/src/modelec_com/src/pcb_odo_interface.cpp +++ b/src/modelec_com/src/pcb_odo_interface.cpp @@ -69,8 +69,8 @@ namespace Modelec SetPIDCallback(msg); }); - cmd_vel_subscriber_ = this->create_subscription( - "cmd_vel", 30, + joy_subscriber_ = this->create_subscription( + "joy", 30, [this](const sensor_msgs::msg::Joy::SharedPtr msg) { double forward = msg->axes[1];