Skip to content

Commit

Permalink
Make joint_states subscription QoS configurable; default to SensorDat…
Browse files Browse the repository at this point in the history
…aQoS. (#179)

This changes the subscription default from `reliable` to
`best_effort`. This is helpful when visualizing a robot that's running
on a wifi-connected device, and eliminates a warning when starting up
drivers on a robot that publishes with `best_effort`.

The subscription defaults to `best_effort`, but can be overridden with
the following config:

```yaml
robot_state_publisher:
  ros__parameters:
    qos_overrides:
      /joint_states:
        subscription:
          reliability: reliable
```
  • Loading branch information
adeschamps committed Oct 26, 2021
1 parent 3612490 commit 8b3f6b8
Showing 1 changed file with 8 additions and 3 deletions.
11 changes: 8 additions & 3 deletions src/robot_state_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,11 +136,16 @@ RobotStatePublisher::RobotStatePublisher(const rclcpp::NodeOptions & options)

setupURDF(urdf_xml);

auto subscriber_options = rclcpp::SubscriptionOptions();
subscriber_options.qos_overriding_options =
rclcpp::QosOverridingOptions::with_default_policies();

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

publishFixedTransforms();

Expand Down

0 comments on commit 8b3f6b8

Please sign in to comment.