Skip to content
This repository has been archived by the owner on Oct 9, 2019. It is now read-only.

Commit

Permalink
changes to avoid deprecated API's (#19)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed May 8, 2019
1 parent 6452835 commit fb08c69
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 7 deletions.
2 changes: 1 addition & 1 deletion src/joint_state_listener.cpp
Expand Up @@ -87,7 +87,7 @@ JointStateListener::JointStateListener(

// subscribe to joint state
joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
"joint_states", std::bind(
"joint_states", 10, std::bind(
&JointStateListener::callbackJointState, this,
std::placeholders::_1));

Expand Down
9 changes: 3 additions & 6 deletions src/robot_state_publisher.cpp
Expand Up @@ -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<std_msgs::msg::String>(
"robot_description", qos);
"robot_description",
// Transient local is similar to latching in ROS 1.
rclcpp::QoS(1).transient_local());
}

// add children to correct maps
Expand Down

0 comments on commit fb08c69

Please sign in to comment.