change API to encourage users to specify history depth always (#713)
* improve interoperability with rclcpp::Duration and std::chrono Signed-off-by: William Woodall <william@osrfoundation.org> * add to_rmw_time to Duration Signed-off-by: William Woodall <william@osrfoundation.org> * add new QoS class to rclcpp Signed-off-by: William Woodall <william@osrfoundation.org> * changes to NodeBase, NodeTopics, etc in preparation for changes to pub/sub Signed-off-by: William Woodall <william@osrfoundation.org> * refactor publisher creation to use new QoS class Signed-off-by: William Woodall <william@osrfoundation.org> * refactor subscription creation to use new QoS class Signed-off-by: William Woodall <william@osrfoundation.org> * fixing fallout from changes to pub/sub creation Signed-off-by: William Woodall <william@osrfoundation.org> * fixed Windows error: no appropriate default constructor available why? who knows Signed-off-by: William Woodall <william@osrfoundation.org> * fixed Windows error: could not deduce template argument for 'PublisherT' Signed-off-by: William Woodall <william@osrfoundation.org> * fix missing vftable linker error on Windows Signed-off-by: William Woodall <william@osrfoundation.org> * fix more cases of no suitable default constructor errors... Signed-off-by: William Woodall <william@osrfoundation.org> * prevent msvc from trying to interpret some cases as functions Signed-off-by: William Woodall <william@osrfoundation.org> * uncrustify Signed-off-by: William Woodall <william@osrfoundation.org> * cpplint Signed-off-by: William Woodall <william@osrfoundation.org> * add C++ version of default action qos Signed-off-by: William Woodall <william@osrfoundation.org> * fixing lifecycle subscription signatures Signed-off-by: William Woodall <william@osrfoundation.org> * fix allocators (we actually use this already in the pub/sub factory) Signed-off-by: William Woodall <william@osrfoundation.org> * suppress cppcheck on false positive syntax error Signed-off-by: William Woodall <william@osrfoundation.org> * fix more cppcheck syntax error false positives Signed-off-by: William Woodall <william@osrfoundation.org> * fix case where sub-type of QoS is used Signed-off-by: William Woodall <william@osrfoundation.org> * fixup get_node_topics_interface.hpp according to reviews and tests Signed-off-by: William Woodall <william@osrfoundation.org> * additional fixes based on local testing and CI Signed-off-by: William Woodall <william@osrfoundation.org> * another trick to avoid 'no appropriate default constructor available' Signed-off-by: William Woodall <william@osrfoundation.org> * fix compiler error with clang on macOS Signed-off-by: William Woodall <william@osrfoundation.org> * disable build failure tests until we can get Jenkins to ignore their output Signed-off-by: William Woodall <william@osrfoundation.org> * suppress more cppcheck false positives Signed-off-by: William Woodall <william@osrfoundation.org> * add missing visibility macros to default QoS profile classes Signed-off-by: William Woodall <william@osrfoundation.org> * fix another case of 'no appropriate default constructor available' Signed-off-by: William Woodall <william@osrfoundation.org> * unfortunately this actaully fixes a build error on Windows... Signed-off-by: William Woodall <william@osrfoundation.org> * fix typos Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
385cccc2cc
commit
c769b1b030
53 changed files with 1908 additions and 454 deletions
|
@ -49,8 +49,11 @@
|
|||
#include "rclcpp/node_interfaces/node_waitables_interface.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/publisher.hpp"
|
||||
#include "rclcpp/publisher_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/service.hpp"
|
||||
#include "rclcpp/subscription.hpp"
|
||||
#include "rclcpp/subscription_options.hpp"
|
||||
#include "rclcpp/time.hpp"
|
||||
#include "rclcpp/timer.hpp"
|
||||
|
||||
|
@ -63,6 +66,29 @@
|
|||
namespace rclcpp_lifecycle
|
||||
{
|
||||
|
||||
// include these here to work around an esoteric Windows error where the namespace
|
||||
// cannot be used in the function declaration below without getting an error like:
|
||||
// 'rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>':
|
||||
// no appropriate default constructor available
|
||||
template<typename AllocatorT>
|
||||
using PublisherOptionsWithAllocator = rclcpp::PublisherOptionsWithAllocator<AllocatorT>;
|
||||
template<typename AllocatorT>
|
||||
using SubscriptionOptionsWithAllocator = rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>;
|
||||
|
||||
template<typename AllocatorT>
|
||||
PublisherOptionsWithAllocator<AllocatorT>
|
||||
create_default_publisher_options()
|
||||
{
|
||||
return rclcpp::PublisherOptionsWithAllocator<AllocatorT>();
|
||||
}
|
||||
|
||||
template<typename AllocatorT>
|
||||
SubscriptionOptionsWithAllocator<AllocatorT>
|
||||
create_default_subscription_options()
|
||||
{
|
||||
return rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>();
|
||||
}
|
||||
|
||||
/// LifecycleNode for creating lifecycle components
|
||||
/**
|
||||
* has lifecycle nodeinterface for configuring this node.
|
||||
|
@ -128,6 +154,22 @@ public:
|
|||
const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
|
||||
get_callback_groups() const;
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos The Quality of Service settings for this publisher.
|
||||
* \param[in] options The publisher options for this publisher.
|
||||
* \return Shared pointer to the created lifecycle publisher.
|
||||
*/
|
||||
template<typename MessageT, typename AllocatorT = std::allocator<void>>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
const PublisherOptionsWithAllocator<AllocatorT> & options =
|
||||
create_default_publisher_options<AllocatorT>()
|
||||
);
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
|
@ -136,10 +178,13 @@ public:
|
|||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
create_publisher(
|
||||
const std::string & topic_name, size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator);
|
||||
|
||||
/// Create and return a LifecyclePublisher.
|
||||
/**
|
||||
|
@ -149,12 +194,44 @@ public:
|
|||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
* \param[in] topic_name The topic to subscribe on.
|
||||
* \param[in] callback The user-defined callback function.
|
||||
* \param[in] qos The quality of service for this subscription.
|
||||
* \param[in] options The subscription options for this subscription.
|
||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||
* \return Shared pointer to the created subscription.
|
||||
*/
|
||||
/* TODO(jacquelinekay):
|
||||
Windows build breaks when static member function passed as default
|
||||
argument to msg_mem_strat, nullptr is a workaround.
|
||||
*/
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
|
||||
create_default_subscription_options<AllocatorT>(),
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT
|
||||
>::SharedPtr
|
||||
msg_mem_strat = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
* \param[in] topic_name The topic to subscribe on.
|
||||
|
@ -174,6 +251,10 @@ public:
|
|||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<MessageT, Alloc>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
|
||||
)]]
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
|
@ -206,14 +287,19 @@ public:
|
|||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<MessageT, Alloc>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
|
||||
)]]
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
CallbackT && callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
bool ignore_local_publications = false,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat = nullptr,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
|
@ -457,6 +543,11 @@ public:
|
|||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
|
||||
get_node_waitables_interface();
|
||||
|
||||
/// Return the NodeOptions used when creating this node.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const rclcpp::NodeOptions &
|
||||
get_node_options() const;
|
||||
|
||||
//
|
||||
// LIFECYCLE COMPONENTS
|
||||
//
|
||||
|
@ -585,7 +676,7 @@ private:
|
|||
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
|
||||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
||||
|
||||
bool use_intra_process_comms_;
|
||||
const rclcpp::NodeOptions node_options_;
|
||||
|
||||
class LifecycleNodeInterfaceImpl;
|
||||
std::unique_ptr<LifecycleNodeInterfaceImpl> impl_;
|
||||
|
|
|
@ -39,18 +39,34 @@
|
|||
namespace rclcpp_lifecycle
|
||||
{
|
||||
|
||||
template<typename MessageT, typename AllocatorT>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>>
|
||||
LifecycleNode::create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
|
||||
{
|
||||
using PublisherT = rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>;
|
||||
return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
|
||||
*this,
|
||||
topic_name,
|
||||
qos,
|
||||
options);
|
||||
}
|
||||
|
||||
template<typename MessageT, typename Alloc>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
LifecycleNode::create_publisher(
|
||||
const std::string & topic_name, size_t qos_history_depth,
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<Alloc>();
|
||||
}
|
||||
rmw_qos_profile_t qos = rmw_qos_profile_default;
|
||||
qos.depth = qos_history_depth;
|
||||
return this->create_publisher<MessageT, Alloc>(topic_name, qos, allocator);
|
||||
rclcpp::PublisherOptionsWithAllocator<Alloc> options;
|
||||
options.allocator = allocator;
|
||||
return this->create_publisher<MessageT, Alloc>(
|
||||
topic_name,
|
||||
rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)),
|
||||
options);
|
||||
}
|
||||
|
||||
template<typename MessageT, typename Alloc>
|
||||
|
@ -60,21 +76,48 @@ LifecycleNode::create_publisher(
|
|||
const rmw_qos_profile_t & qos_profile,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
using PublisherT = rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>;
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
// create regular publisher in rclcpp::Node
|
||||
return rclcpp::create_publisher<MessageT, Alloc, PublisherT>(
|
||||
this->node_topics_.get(),
|
||||
rclcpp::PublisherOptionsWithAllocator<Alloc> pub_options;
|
||||
pub_options.allocator = allocator;
|
||||
|
||||
return this->create_publisher<MessageT, Alloc>(
|
||||
topic_name,
|
||||
qos_profile,
|
||||
rclcpp::PublisherEventCallbacks(),
|
||||
nullptr,
|
||||
use_intra_process_comms_,
|
||||
allocator);
|
||||
qos,
|
||||
pub_options);
|
||||
}
|
||||
|
||||
// TODO(karsten1987): Create LifecycleSubscriber
|
||||
template<typename MessageT, typename CallbackT, typename Alloc, typename SubscriptionT>
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename AllocatorT,
|
||||
typename SubscriptionT>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
LifecycleNode::create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT>::SharedPtr
|
||||
msg_mem_strat)
|
||||
{
|
||||
return rclcpp::create_subscription<MessageT>(
|
||||
*this,
|
||||
topic_name,
|
||||
qos,
|
||||
std::forward<CallbackT>(callback),
|
||||
options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename Alloc,
|
||||
typename SubscriptionT>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
LifecycleNode::create_subscription(
|
||||
const std::string & topic_name,
|
||||
|
@ -87,28 +130,16 @@ LifecycleNode::create_subscription(
|
|||
msg_mem_strat,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
using CallbackMessageT = typename rclcpp::subscription_traits::has_message_type<CallbackT>::type;
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<Alloc>();
|
||||
}
|
||||
rclcpp::SubscriptionOptionsWithAllocator<Alloc> sub_options;
|
||||
sub_options.callback_group = group;
|
||||
sub_options.ignore_local_publications = ignore_local_publications;
|
||||
sub_options.allocator = allocator;
|
||||
|
||||
if (!msg_mem_strat) {
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
msg_mem_strat = MessageMemoryStrategy<CallbackMessageT, Alloc>::create_default();
|
||||
}
|
||||
|
||||
return rclcpp::create_subscription<MessageT, CallbackT, Alloc, CallbackMessageT, SubscriptionT>(
|
||||
this->node_topics_.get(),
|
||||
topic_name,
|
||||
std::forward<CallbackT>(callback),
|
||||
qos_profile,
|
||||
rclcpp::SubscriptionEventCallbacks(),
|
||||
group,
|
||||
ignore_local_publications,
|
||||
use_intra_process_comms_,
|
||||
msg_mem_strat,
|
||||
allocator);
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
|
||||
topic_name, std::forward<CallbackT>(callback), qos, sub_options, msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
|
@ -123,21 +154,22 @@ LifecycleNode::create_subscription(
|
|||
CallbackT && callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
bool ignore_local_publications,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
rmw_qos_profile_t qos = rmw_qos_profile_default;
|
||||
qos.depth = qos_history_depth;
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc>(
|
||||
rclcpp::SubscriptionOptionsWithAllocator<Alloc> sub_options;
|
||||
sub_options.callback_group = group;
|
||||
sub_options.ignore_local_publications = ignore_local_publications;
|
||||
sub_options.allocator = allocator;
|
||||
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
|
||||
topic_name,
|
||||
std::forward<CallbackT>(callback),
|
||||
qos,
|
||||
rclcpp::SubscriptionEventCallbacks(),
|
||||
group,
|
||||
ignore_local_publications,
|
||||
msg_mem_strat,
|
||||
allocator);
|
||||
rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)),
|
||||
sub_options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<typename DurationRepT, typename DurationT, typename CallbackT>
|
||||
|
|
|
@ -68,7 +68,11 @@ LifecycleNode::LifecycleNode(
|
|||
const std::string & namespace_,
|
||||
const rclcpp::NodeOptions & options)
|
||||
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
||||
node_name, namespace_, options)),
|
||||
node_name,
|
||||
namespace_,
|
||||
options.context(),
|
||||
*(options.get_rcl_node_options()),
|
||||
options.use_intra_process_comms())),
|
||||
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
||||
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||
|
@ -88,10 +92,10 @@ LifecycleNode::LifecycleNode(
|
|||
node_services_,
|
||||
node_clock_,
|
||||
options.initial_parameters(),
|
||||
options.use_intra_process_comms(),
|
||||
options.start_parameter_services(),
|
||||
options.start_parameter_event_publisher(),
|
||||
options.parameter_event_qos_profile(),
|
||||
options.parameter_event_qos(),
|
||||
options.parameter_event_publisher_options(),
|
||||
options.allow_undeclared_parameters(),
|
||||
options.automatically_declare_initial_parameters()
|
||||
)),
|
||||
|
@ -105,7 +109,7 @@ LifecycleNode::LifecycleNode(
|
|||
node_parameters_
|
||||
)),
|
||||
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
||||
use_intra_process_comms_(options.use_intra_process_comms()),
|
||||
node_options_(options),
|
||||
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
||||
{
|
||||
impl_->init();
|
||||
|
@ -333,6 +337,11 @@ LifecycleNode::get_node_waitables_interface()
|
|||
return node_waitables_;
|
||||
}
|
||||
|
||||
const rclcpp::NodeOptions &
|
||||
LifecycleNode::get_node_options() const
|
||||
{
|
||||
return node_options_;
|
||||
}
|
||||
|
||||
////
|
||||
bool
|
||||
|
|
|
@ -217,7 +217,8 @@ TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
|
|||
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
|
||||
|
||||
auto cb = [](const std::shared_ptr<lifecycle_msgs::msg::State> msg) {(void) msg;};
|
||||
auto lifecycle_sub = test_node->create_subscription<lifecycle_msgs::msg::State>("~/empty", cb);
|
||||
auto lifecycle_sub =
|
||||
test_node->create_subscription<lifecycle_msgs::msg::State>("~/empty", 10, cb);
|
||||
|
||||
SUCCEED();
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue