Skip to content

Commit

Permalink
Fix unused QoS profile for clock subscription and make ClockQoS the d…
Browse files Browse the repository at this point in the history
…efault
  • Loading branch information
nnmm committed Oct 13, 2021
1 parent 3019575 commit d336613
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/node_interfaces/node_time_source.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class NodeTimeSource : public NodeTimeSourceInterface
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters,
const rclcpp::QoS & qos = rclcpp::RosoutQoS(),
const rclcpp::QoS & qos = rclcpp::ClockQoS(),
bool use_clock_thread = true
);

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,7 @@ void TimeSource::create_clock_sub()
node_parameters_,
node_topics_,
"/clock",
rclcpp::QoS(KeepLast(1)).best_effort(),
qos_,
std::bind(&TimeSource::clock_cb, this, std::placeholders::_1),
options
);
Expand Down

0 comments on commit d336613

Please sign in to comment.