From fb08c69118f53c52a8463f9f099a7bf6d29abb67 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Wed, 8 May 2019 14:25:07 -0700 Subject: [PATCH] changes to avoid deprecated API's (#19) Signed-off-by: William Woodall --- src/joint_state_listener.cpp | 2 +- src/robot_state_publisher.cpp | 9 +++------ 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/src/joint_state_listener.cpp b/src/joint_state_listener.cpp index 4b7811e..5c3b59d 100644 --- a/src/joint_state_listener.cpp +++ b/src/joint_state_listener.cpp @@ -87,7 +87,7 @@ JointStateListener::JointStateListener( // subscribe to joint state joint_state_sub_ = node_->create_subscription( - "joint_states", std::bind( + "joint_states", 10, std::bind( &JointStateListener::callbackJointState, this, std::placeholders::_1)); diff --git a/src/robot_state_publisher.cpp b/src/robot_state_publisher.cpp index 3d47a95..6317e64 100644 --- a/src/robot_state_publisher.cpp +++ b/src/robot_state_publisher.cpp @@ -81,15 +81,12 @@ RobotStatePublisher::RobotStatePublisher( // walk the tree and add segments to segments_ addChildren(tree.getRootSegment()); - // Creates a latched topic - rmw_qos_profile_t qos = rmw_qos_profile_default; - qos.depth = 1; - qos.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; - model_xml_.data = model_xml; node_handle->declare_parameter("robot_description", model_xml); description_pub_ = node_handle->create_publisher( - "robot_description", qos); + "robot_description", + // Transient local is similar to latching in ROS 1. + rclcpp::QoS(1).transient_local()); } // add children to correct maps