From e866e2342f43b23704ecf962fcc2af0898421d35 Mon Sep 17 00:00:00 2001 From: Michael Wimble Date: Sat, 25 Jun 2022 19:17:13 -0700 Subject: [PATCH] Change QOS policy to RELIABLE/VOLATILE to match subscribers. Change topic name to puck_joint_states --- src/motor_driver.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/motor_driver.cpp b/src/motor_driver.cpp index 7d78676..e60559f 100755 --- a/src/motor_driver.cpp +++ b/src/motor_driver.cpp @@ -9,6 +9,7 @@ #include #include #include +#include #include #include @@ -146,8 +147,8 @@ void MotorDriver::onInit(rclcpp::Node::SharedPtr node) { auto qos = rclcpp::QoS( rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, 10)); - qos.reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT); - qos.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); + qos.reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE); + qos.durability(rclcpp::DurabilityPolicy::Volatile); qos.avoid_ros_namespace_conventions(false); cmdVelSub_ = node_->create_subscription( @@ -156,7 +157,7 @@ void MotorDriver::onInit(rclcpp::Node::SharedPtr node) { if (publish_joint_states_) { joint_state_publisher_ = - this->create_publisher("JointStates", + this->create_publisher("puck_joint_states", qos); }