Skip to content

Commit

Permalink
Qos configurability (take 2) (#1465)
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno committed Nov 17, 2020
1 parent add6d61 commit 71a58d4
Show file tree
Hide file tree
Showing 16 changed files with 1,109 additions and 55 deletions.
1 change: 1 addition & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/publisher_base.cpp
src/rclcpp/qos.cpp
src/rclcpp/qos_event.cpp
src/rclcpp/qos_overriding_options.cpp
src/rclcpp/serialization.cpp
src/rclcpp/serialized_message.cpp
src/rclcpp/service.cpp
Expand Down
78 changes: 66 additions & 12 deletions rclcpp/include/rclcpp/create_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,54 +17,108 @@

#include <memory>
#include <string>
#include <utility>

#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
#include "rclcpp/node_options.hpp"
#include "rclcpp/publisher_factory.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/qos_overriding_options.hpp"
#include "rclcpp/detail/qos_parameters.hpp"

#include "rmw/qos_profiles.h"

namespace rclcpp
{

namespace detail
{
/// Create and return a publisher of the given MessageT type.
/**
* The NodeT type only needs to have a method called get_node_topics_interface()
* which returns a shared_ptr to a NodeTopicsInterface.
*/
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>,
typename NodeT>
typename NodeParametersT,
typename NodeTopicsT>
std::shared_ptr<PublisherT>
create_publisher(
NodeT & node,
NodeParametersT & node_parameters,
NodeTopicsT & node_topics,
const std::string & topic_name,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
)
{
// Extract the NodeTopicsInterface from the NodeT.
using rclcpp::node_interfaces::get_node_topics_interface;
auto node_topics = get_node_topics_interface(node);
auto node_topics_interface = rclcpp::node_interfaces::get_node_topics_interface(node_topics);
const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
rclcpp::detail::declare_qos_parameters(
options.qos_overriding_options, node_parameters,
node_topics_interface->resolve_topic_name(topic_name),
qos, rclcpp::detail::PublisherQosParametersTraits{}) :
qos;

// Create the publisher.
auto pub = node_topics->create_publisher(
auto pub = node_topics_interface->create_publisher(
topic_name,
rclcpp::create_publisher_factory<MessageT, AllocatorT, PublisherT>(options),
qos
actual_qos
);

// Add the publisher to the node topics interface.
node_topics->add_publisher(pub, options.callback_group);
node_topics_interface->add_publisher(pub, options.callback_group);

return std::dynamic_pointer_cast<PublisherT>(pub);
}
} // namespace detail


/// Create and return a publisher of the given MessageT type.
/**
* The NodeT type only needs to have a method called get_node_topics_interface()
* which returns a shared_ptr to a NodeTopicsInterface.
*/
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>,
typename NodeT>
std::shared_ptr<PublisherT>
create_publisher(
NodeT & node,
const std::string & topic_name,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
)
{
return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
node, node, topic_name, qos, options);
}

/// Create and return a publisher of the given MessageT type.
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr<PublisherT>
create_publisher(
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
const std::string & topic_name,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
)
{
return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
node_parameters, node_topics, topic_name, qos, options);
}

} // namespace rclcpp

Expand Down
162 changes: 119 additions & 43 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,44 +41,21 @@
namespace rclcpp
{

/// Create and return a subscription of the given MessageT type.
/**
* The NodeT type only needs to have a method called get_node_topics_interface()
* which returns a shared_ptr to a NodeTopicsInterface, or be a
* NodeTopicsInterface pointer itself.
*
* \tparam MessageT
* \tparam CallbackT
* \tparam AllocatorT
* \tparam CallbackMessageT
* \tparam SubscriptionT
* \tparam MessageMemoryStrategyT
* \tparam NodeT
* \param node
* \param topic_name
* \param qos
* \param callback
* \param options
* \param msg_mem_strat
* \return the created subscription
* \throws std::invalid_argument if topic statistics is enabled and the publish period is
* less than or equal to zero.
*/
namespace detail
{
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename CallbackMessageT =
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT,
AllocatorT
>,
typename NodeT>
typename AllocatorT,
typename CallbackMessageT,
typename SubscriptionT,
typename MessageMemoryStrategyT,
typename NodeParametersT,
typename NodeTopicsT>
typename std::shared_ptr<SubscriptionT>
create_subscription(
NodeT && node,
NodeParametersT & node_parameters,
NodeTopicsT & node_topics,
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
Expand All @@ -91,14 +68,14 @@ create_subscription(
)
{
using rclcpp::node_interfaces::get_node_topics_interface;
auto node_topics = get_node_topics_interface(std::forward<NodeT>(node));
auto node_topics_interface = get_node_topics_interface(node_topics);

std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>>
subscription_topic_stats = nullptr;

if (rclcpp::detail::resolve_enable_topic_statistics(
options,
*node_topics->get_node_base_interface()))
*node_topics_interface->get_node_base_interface()))
{
if (options.topic_stats_options.publish_period <= std::chrono::milliseconds(0)) {
throw std::invalid_argument(
Expand All @@ -107,15 +84,16 @@ create_subscription(
" ms");
}

std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>> publisher =
create_publisher<statistics_msgs::msg::MetricsMessage>(
node,
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);

subscription_topic_stats = std::make_shared<
rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
>(node_topics->get_node_base_interface()->get_name(), publisher);
>(node_topics_interface->get_node_base_interface()->get_name(), publisher);

std::weak_ptr<
rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
Expand All @@ -127,14 +105,14 @@ create_subscription(
}
};

auto node_timer_interface = node_topics->get_node_timers_interface();
auto node_timer_interface = node_topics_interface->get_node_timers_interface();

auto timer = create_wall_timer(
std::chrono::duration_cast<std::chrono::nanoseconds>(
options.topic_stats_options.publish_period),
sub_call_back,
options.callback_group,
node_topics->get_node_base_interface(),
node_topics_interface->get_node_base_interface(),
node_timer_interface
);

Expand All @@ -148,11 +126,109 @@ create_subscription(
subscription_topic_stats
);

auto sub = node_topics->create_subscription(topic_name, factory, qos);
node_topics->add_subscription(sub, options.callback_group);
const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
rclcpp::detail::declare_qos_parameters(
options.qos_overriding_options, node_parameters,
node_topics_interface->resolve_topic_name(topic_name),
qos, rclcpp::detail::SubscriptionQosParametersTraits{}) :
qos;

auto sub = node_topics_interface->create_subscription(topic_name, factory, actual_qos);
node_topics_interface->add_subscription(sub, options.callback_group);

return std::dynamic_pointer_cast<SubscriptionT>(sub);
}
} // namespace detail

/// Create and return a subscription of the given MessageT type.
/**
* The NodeT type only needs to have a method called get_node_topics_interface()
* which returns a shared_ptr to a NodeTopicsInterface, or be a
* NodeTopicsInterface pointer itself.
*
* \tparam MessageT
* \tparam CallbackT
* \tparam AllocatorT
* \tparam CallbackMessageT
* \tparam SubscriptionT
* \tparam MessageMemoryStrategyT
* \tparam NodeT
* \param node
* \param topic_name
* \param qos
* \param callback
* \param options
* \param msg_mem_strat
* \return the created subscription
* \throws std::invalid_argument if topic statistics is enabled and the publish period is
* less than or equal to zero.
*/
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename CallbackMessageT =
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT,
AllocatorT
>,
typename NodeT>
typename std::shared_ptr<SubscriptionT>
create_subscription(
NodeT & node,
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
),
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
)
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
node, node, topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
}

/// Create and return a subscription of the given MessageT type.
/**
* See \ref create_subscription().
*/
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename CallbackMessageT =
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT,
AllocatorT
>>
typename std::shared_ptr<SubscriptionT>
create_subscription(
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
),
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
)
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
node_parameters, node_topics, topic_name, qos,
std::forward<CallbackT>(callback), options, msg_mem_strat);
}

} // namespace rclcpp

Expand Down
Loading

0 comments on commit 71a58d4

Please sign in to comment.