Skip to content

Commit

Permalink
Update rclcpp functionality to use new interfaces (#4)
Browse files Browse the repository at this point in the history
* New interfaces for incoming QoS features

Adds new PublisherOptions and SubscriptionOptions classes, with new Publisher and Subscriber constructors
to accept them. Adds the liveliness assertion callbacks that will be needed for the new Liveliness QoS policy

Signed-off-by: Emerson Knapp <eknapp@amazon.com>

* Fix options usage in implementation, and add test to catch that code path.

Signed-off-by: Emerson Knapp <eknapp@amazon.com>

* rclcpp QoS implementation (#2)

* Add interfaces for events in memory_strategy

Signed-off-by: Miaofei <miaofei@amazon.com>

* refactor waitables

Signed-off-by: Miaofei <miaofei@amazon.com>

* Attempt to fix cppcheck (ros2#646)

Signed-off-by: Shane Loretz <sloretz@osrfoundation.org>

* add event callbacks to publisher, subscriber, client, service

Signed-off-by: Miaofei <miaofei@amazon.com>

* fix some ros2 build issues

Signed-off-by: Miaofei <miaofei@amazon.com>

* Add a method to the LifecycleNode class to get the logging interface (ros2#652)

There are getters for the other interfaces, but the logging interface
appears to have been overlooked.

Signed-off-by: Michael Jeronimo <michael.jeronimo@intel.com>

* Add Doxyfile for rclcpp_action

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Add documentation to rclcpp_action

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* update to use separated action types (ros2#601)

* match renamed action types

* fix action type casting

* rename type/field to use correct term

* rename custom GoalID type to avoid naming collision, update types using unique_identifier_msgs

* remove obsolete comments

* change signature of set_succeeded / set_canceled

* change signature of     on_terminal_state_(uuid_, result_msg);set_succeeded / set_canceled

* change signature of set_aborted

* change signature of publish_feedback

* update another test

Signed-off-by: Miaofei <miaofei@amazon.com>

* update client-facing API

Signed-off-by: Miaofei <miaofei@amazon.com>

* Don't hardcode int64_t for duration type representations (ros2#648)

In LLVM's `libcxx`, `int64_t` doesn't match chrono literals. See example below. To compile, run  `clang++-6.0 -stdlib=libc++ -std=c++14 TEST.cpp`

```
using namespace std::chrono_literals;

template<typename RatioT = std::milli>
bool
wait_for_service(
   std::chrono::duration<int64_t, RatioT> timeout
)
{
   return timeout == std::chrono::nanoseconds(0);
}

int main() {
   wait_for_service(2s);
   return 0;
}

```

Result of compilation
```
TEST.cpp:6:1: note: candidate template ignored: could not match 'long' against 'long long'
wait_for_service(
```

Signed-off-by: Emerson Knapp <eknapp@amazon.com>
Signed-off-by: Steven! Ragnarök <steven@nuclearsandwich.com>

* improve usability of the SubscriptionOptions and PublisherOptions classes

Signed-off-by: Miaofei <miaofei@amazon.com>

* Fix test_time_source test (ros2#639)

* Fix flakey test

Signed-off-by: Pete Baughman <pete.baughman@apex.ai>

* Fix lint and uncrustify issues

Signed-off-by: Pete Baughman <pete.baughman@apex.ai>

* fix lint errors

Signed-off-by: Miaofei <miaofei@amazon.com>

* apply uncrustify

Signed-off-by: Miaofei <miaofei@amazon.com>

* add section about DCO to CONTRIBUTING.md

* update for rcl API changes

Signed-off-by: Miaofei <miaofei@amazon.com>

* Fix lint and build warnings and API inconsistency

Signed-off-by: Emerson Knapp <eknapp@amazon.com>

* Avoid race that triggers timer too often (ros2#621)

The two distinct operations of acquiring and subsequent checking of a
timer have to be protected by one lock_guard against races with other
threads. The releasing of a timer has to be protected by the same lock.

Given this requirement there is no use for a second mutex.

Signed-off-by: Marko Durkovic <marko@ternaris.com>

* Back out Waitable and GraphEvent-related changes

Signed-off-by: Emerson Knapp <eknapp@amazon.com>

* add publisher and subscription events to AllocatorMemoryStrategy

* Add stub API for assert_liveliness

* Fix use_sim_time issue on LifeCycleNode (ros2#651)

Signed-off-by: vinnamkim <vinnam.kim@gmail.com>

* revert changes to client and services
address PR comments

Signed-off-by: Miaofei <miaofei@amazon.com>

* Add parameter-related templates to LifecycleNode (ros2#645)

* Add parameter-related templates to LifecycleNode

Signed-off-by: vinnamkim <vinnam.kim@gmail.com>

* Update rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp

Co-Authored-By: vinnamkim <vinnam.kim@gmail.com>

* Update rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp

* update API calls into rcl

* fix linter errors in rclcpp_lifecycle (ros2#672)

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* Update to use the new interface definitions

Signed-off-by: Emerson Knapp <eknapp@amazon.com>

* Remove duplicate event_handlers_
  • Loading branch information
emersonknapp authored and mm318 committed Apr 2, 2019
1 parent d8502a7 commit c177718
Show file tree
Hide file tree
Showing 12 changed files with 324 additions and 355 deletions.
9 changes: 9 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -249,6 +249,15 @@ if(BUILD_TESTING)
)
target_link_libraries(test_publisher ${PROJECT_NAME})
endif()
ament_add_gtest(test_pub_sub_option_interface test/test_pub_sub_option_interface.cpp)
if(TARGET test_pub_sub_option_interface)
ament_target_dependencies(test_pub_sub_option_interface
test_msgs
)
target_link_libraries(test_pub_sub_option_interface
${PROJECT_NAME}
)
endif()
ament_add_gtest(test_publisher_subscription_count_api test/test_publisher_subscription_count_api.cpp)
if(TARGET test_publisher_subscription_count_api)
ament_target_dependencies(test_publisher_subscription_count_api
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ create_subscription(
auto factory = rclcpp::create_subscription_factory
<MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT>(
std::forward<CallbackT>(callback),
event_callbacks,
event_callbacks,
msg_mem_strat,
allocator);

Expand Down
98 changes: 92 additions & 6 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,24 +139,84 @@ class Node : public std::enable_shared_from_this<Node>
const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
get_callback_groups() const;

/// Create and return a Publisher.
/// Create and return a Publisher. Note: This constructor is deprecated
/**
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] group The callback group for this publisher. NULL for no callback group.
* \param[in] options Additional options to control creation of the publisher.
* \return Shared pointer to the created publisher.
*/
template<
typename MessageT, typename Alloc = std::allocator<void>,
typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
std::shared_ptr<PublisherT>
create_publisher(
const std::string & topic_name,
size_t qos_history_depth,
std::shared_ptr<Alloc> allocator = nullptr);

/// Create and return a Publisher. Note: this constructor is deprecated
/**
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] allocator Optional custom allocator.
* \return Shared pointer to the created publisher.
*/
template<
typename MessageT, typename Alloc = std::allocator<void>,
typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
std::shared_ptr<PublisherT>
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 Publisher.
/**
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] options Additional options for the created Publisher
* \return Shared pointer to the created publisher.
*/
template<
typename MessageT,
typename Alloc = std::allocator<void>,
typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
std::shared_ptr<PublisherT>
create_publisher(
const std::string & topic_name,
const PublisherOptions<Alloc> & options,
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group = nullptr);

/// Create and return a Subscription. Note: this constructor is deprecated
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] callback The user-defined callback function.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \param[in] allocator Optional custom allocator.
* \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 Alloc = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
const PublisherOptions<Alloc> & options = PublisherOptions<Alloc>());

/// Create and return a Subscription.
/// Create and return a Subscription. Note: this constructor is deprecated
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] callback The user-defined callback function.
Expand Down Expand Up @@ -185,6 +245,34 @@ class Node : public std::enable_shared_from_this<Node>
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
msg_mem_strat = nullptr);

/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] callback The user-defined callback function to receive a message
* \param[in] options Additional options for the creation of the 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 Alloc = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
CallbackT && callback,
const SubscriptionOptions<Alloc> & options,
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group = nullptr,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
msg_mem_strat = nullptr);

/// Create a timer.
/**
* \param[in] period Time interval between triggers of the callback.
Expand Down Expand Up @@ -549,13 +637,11 @@ class Node : public std::enable_shared_from_this<Node>
const NodeOptions &
get_node_options() const;


/// Manually assert that this Node is alive (for RMW_QOS_POLICY_MANUAL_BY_NODE)
/**
* If the rmw Liveliness policy is set to RMW_QOS_POLICY_MANUAL_BY_NODE, the creator of this
* node must manually call `assert_liveliness` on a regular basis to signal to the rest of the
* system that this Node is still alive.
* This function must be called at least as often as the qos_profile's liveliness_lease_duration
* Node must manually call `assert_liveliness` periodically to signal that this Node
* is still alive. Must be called at least as often as qos_profile's Liveliness lease_duration
*/
RCLCPP_PUBLIC
void
Expand Down
121 changes: 114 additions & 7 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,21 @@
namespace rclcpp
{

template<typename MessageT, typename Alloc, typename PublisherT>
std::shared_ptr<PublisherT>
Node::create_publisher(
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, PublisherT>(topic_name, qos, allocator);
}

RCLCPP_LOCAL
inline
std::string
Expand All @@ -67,8 +82,8 @@ template<typename MessageT, typename Alloc, typename PublisherT>
std::shared_ptr<PublisherT>
Node::create_publisher(
const std::string & topic_name,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
const PublisherOptions<Alloc> & options)
const rmw_qos_profile_t & qos_profile,
std::shared_ptr<Alloc> allocator)
{
std::shared_ptr<Alloc> allocator = options.allocator();
if (!allocator) {
Expand All @@ -78,8 +93,30 @@ Node::create_publisher(
return rclcpp::create_publisher<MessageT, Alloc, PublisherT>(
this->node_topics_.get(),
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
options.qos_profile(),
options.event_callbacks(),
qos_profile,
PublisherEventCallbacks(),
nullptr,
this->get_node_options().use_intra_process_comms(),
allocator);
}

template<typename MessageT, typename Alloc, typename PublisherT>
std::shared_ptr<PublisherT>
Node::create_publisher(
const std::string & topic_name,
const PublisherOptions<Alloc> & options,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
{
std::shared_ptr<Alloc> allocator = options.allocator;
if (!allocator) {
allocator = std::make_shared<Alloc>();
}

return rclcpp::create_publisher<MessageT, Alloc, PublisherT>(
this->node_topics_.get(),
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
options.qos_profile,
options.event_callbacks,
group,
this->get_node_options().use_intra_process_comms(),
allocator);
Expand All @@ -94,8 +131,8 @@ std::shared_ptr<SubscriptionT>
Node::create_subscription(
const std::string & topic_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
const SubscriptionOptions<Alloc> & options,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
msg_mem_strat)
Expand All @@ -116,15 +153,85 @@ Node::create_subscription(
this->node_topics_.get(),
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
std::forward<CallbackT>(callback),
options.qos_profile(),
options.event_callbacks(),
qos_profile,
SubscriptionEventCallbacks(),
group,
options.ignore_local_publications(),
this->get_node_options().use_intra_process_comms(),
msg_mem_strat,
allocator);
}

template<
typename MessageT,
typename CallbackT,
typename Alloc,
typename SubscriptionT>
std::shared_ptr<SubscriptionT>
Node::create_subscription(
const std::string & topic_name,
CallbackT && callback,
const SubscriptionOptions<Alloc> & options,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
msg_mem_strat)
{
using CallbackMessageT = typename rclcpp::subscription_traits::has_message_type<CallbackT>::type;

std::shared_ptr<Alloc> allocator = options.allocator;
if (!allocator) {
allocator = std::make_shared<Alloc>();
}

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(),
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
std::forward<CallbackT>(callback),
options.qos_profile,
options.event_callbacks,
group,
options.ignore_local_publications,
this->get_node_options().use_intra_process_comms(),
msg_mem_strat,
allocator);
}

template<
typename MessageT,
typename CallbackT,
typename Alloc,
typename SubscriptionT>
std::shared_ptr<SubscriptionT>
Node::create_subscription(
const std::string & topic_name,
CallbackT && callback,
size_t qos_history_depth,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
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>(
topic_name,
std::forward<CallbackT>(callback),
qos,
group,
ignore_local_publications,
msg_mem_strat,
allocator);
}

template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
Node::create_wall_timer(
Expand Down
Loading

0 comments on commit c177718

Please sign in to comment.