Skip to content

Commit

Permalink
Make use of qos overrides in some default topics
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
  • Loading branch information
ivanpauno committed Oct 21, 2020
1 parent 4d6ad65 commit 584e9f8
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 3 deletions.
4 changes: 3 additions & 1 deletion rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,12 +84,14 @@ create_subscription(
" ms");
}

// TODO(ivanpauno): This could have topics statistics enabled, but I'm not sure if it makes
// sense.
std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>> publisher =
rclcpp::detail::create_publisher<statistics_msgs::msg::MetricsMessage>(
node_parameters,
node_topics_interface,
options.topic_stats_options.publish_topic,
qos); // why the topics statistics publisher is using the same QoS as the subscription??
qos);

subscription_topic_stats = std::make_shared<
rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/detail/qos_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,8 @@ declare_qos_parameters(
return qos;
}

// TODO(ivanpauno): This overload cannot declare the QoS parameters, as a node parameters interface
// was not provided.
template<typename NodeT, typename EntityQosParametersTraits>
std::enable_if_t<
!rclcpp::node_interfaces::has_node_parameters_interface<
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/qos_overriding_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,8 @@ struct QosOverridingOptions
* \param policy_kinds list of policy kinds that will be reconfigurable.
* \param id id of the entity.
*/

QosOverridingOptions(std::initializer_list<QosPolicyKind> policy_kinds, std::string id = {});

/// Construct passing a list of qos policies that and a verification callback.
/**
* This constructor is implicit, e.g.:
Expand Down
1 change: 1 addition & 0 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ NodeParameters::NodeParameters(
}

if (start_parameter_event_publisher) {
// TODO(ivanpauno): Qos of the `/parameters_event` topic should be somehow overridable.
events_publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
node_topics,
"/parameter_events",
Expand Down
9 changes: 8 additions & 1 deletion rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "rclcpp/node.hpp"
#include "rclcpp/parameter_client.hpp"
#include "rclcpp/parameter_events_filter.hpp"
#include "rclcpp/subscription_options.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/time_source.hpp"

Expand Down Expand Up @@ -233,11 +234,17 @@ void TimeSource::create_clock_sub()
return;
}

using rclcpp::QosPolicyKind;
rclcpp::SubscriptionOptions options;
options.qos_overriding_options = QosOverridingOptions{
QosPolicyKind::Depth, QosPolicyKind::History, QosPolicyKind::LivelinessLeaseDuration,
QosPolicyKind::Reliability};
clock_subscription_ = rclcpp::create_subscription<rosgraph_msgs::msg::Clock>(
node_topics_,
"/clock",
rclcpp::QoS(KeepLast(1)).best_effort(),
std::bind(&TimeSource::clock_cb, this, std::placeholders::_1)
std::bind(&TimeSource::clock_cb, this, std::placeholders::_1),
options
);
}

Expand Down

0 comments on commit 584e9f8

Please sign in to comment.