diff --git a/.github/workflows/mirror-rolling-to-master.yaml b/.github/workflows/mirror-rolling-to-master.yaml new file mode 100644 index 0000000000..2885eb4a4f --- /dev/null +++ b/.github/workflows/mirror-rolling-to-master.yaml @@ -0,0 +1,13 @@ +name: Mirror rolling to master + +on: + push: + branches: [ rolling ] + +jobs: + mirror-to-master: + runs-on: ubuntu-latest + steps: + - uses: zofrex/mirror-branch@v1 + with: + target-branch: master diff --git a/CODEOWNERS b/CODEOWNERS new file mode 100644 index 0000000000..7ee4b9af4d --- /dev/null +++ b/CODEOWNERS @@ -0,0 +1,2 @@ +# This file was generated by https://github.com/audrow/update-ros2-repos +* @ivanpauno @hidmic @wjwwood diff --git a/README.md b/README.md index 0226a75f0a..f4fe5837aa 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,8 @@ rclcpp provides the standard C++ API for interacting with ROS 2. `#include "rclcpp/rclcpp.hpp"` allows use of the most common elements of the ROS 2 system. -Visit the [rclcpp API documentation](http://docs.ros2.org/latest/api/rclcpp/) for a complete list of its main components. +The link to the latest API documentation can be found on the rclcpp package info page, at the [ROS Index](https://index.ros.org/p/rclcpp/). + ### Examples diff --git a/rclcpp/CHANGELOG.rst b/rclcpp/CHANGELOG.rst index 76ba0e5c4c..0c8201217c 100644 --- a/rclcpp/CHANGELOG.rst +++ b/rclcpp/CHANGELOG.rst @@ -2,6 +2,65 @@ Changelog for package rclcpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +18.0.0 (2022-12-29) +------------------- +* Implement Unified Node Interface (NodeInterfaces class) (`#2041 `_) +* Do not throw exception if trying to dequeue an empty intra-process buffer (`#2061 `_) +* Move event callback binding to PublisherBase and SubscriptionBase (`#2066 `_) +* Implement validity checks for rclcpp::Clock (`#2040 `_) +* Explicitly set callback type (`#2059 `_) +* Fix logging macros to build with msvc and cpp20 (`#2063 `_) +* Add clock type to node_options (`#1982 `_) +* Fix nullptr dereference in prune_requests_older_than (`#2008 `_) +* Remove templating on to_rcl_subscription_options (`#2056 `_) +* Fix SharedFuture from async_send_request never becoming valid (`#2044 `_) +* Add in a warning for a KeepLast depth of 0. (`#2048 `_) +* Mark rclcpp::Clock::now() as const (`#2050 `_) +* Fix a case that did not throw ParameterUninitializedException (`#2036 `_) +* Update maintainers (`#2043 `_) +* Contributors: Alberto Soragna, Audrow Nash, Chen Lihui, Chris Lalancette, Jeffery Hsu, Lei Liu, Mateusz Szczygielski, Shane Loretz, andrei, mauropasse, methylDragon + +17.1.0 (2022-11-02) +------------------- +* MultiThreadExecutor number of threads is at least 2+ in default. (`#2032 `_) +* Fix bug that a callback not reached (`#1640 `_) +* Set the minimum number of threads of the Multithreaded executor to 2 (`#2030 `_) +* check thread whether joinable before join (`#2019 `_) +* Set cpplint test timeout to 3 minutes (`#2022 `_) +* Make sure to include-what-you-use in the node_interfaces. (`#2018 `_) +* Do not clear entities callbacks on destruction (`#2002 `_) +* fix mismatched issue if using zero_allocate (`#1995 `_) +* Contributors: Alexis Paques, Chen Lihui, Chris Lalancette, Cristóbal Arroyo, Tomoya Fujita, mauropasse, uupks + +17.0.0 (2022-09-13) +------------------- +* Make ParameterService and Sync/AsyncParameterClient accept rclcpp::QoS (`#1978 `_) +* support regex match for parameter client (`#1992 `_) +* operator+= and operator-= for Duration (`#1988 `_) +* Revert "Revert "Add a create_timer method to Node and `LifecycleNode` classes (`#1975 `_)" (`#2009 `_) (`#2010 `_) +* force compiler warning if callback handles not captured (`#2000 `_) +* Revert "Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 `_)" (`#2009 `_) +* Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 `_) +* [docs] add note about callback lifetime for {on, post}_set_parameter_callback (`#1981 `_) +* fix memory leak (`#1994 `_) +* Support pre-set and post-set parameter callbacks in addition to on-set-parameter-callback. (`#1947 `_) +* Make create_service accept rclcpp::QoS (`#1969 `_) +* Make create_client accept rclcpp::QoS (`#1964 `_) +* Fix the documentation for rclcpp::ok to be accurate. (`#1965 `_) +* use regex for wildcard matching (`#1839 `_) +* Revert "Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 `_) (`#1874 `_)" (`#1956 `_) +* Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 `_) (`#1874 `_) +* test adjustment for LoanedMessage. (`#1951 `_) +* fix virtual dispatch issues identified by clang-tidy (`#1816 `_) +* Remove unused on_parameters_set_callback\_ (`#1945 `_) +* Fix subscription.is_serialized() for callbacks with message info (`#1950 `_) +* wait for subscriptions on another thread. (`#1940 `_) +* Fix documentation of `RCLCPP\_[INFO,WARN,...]` (`#1943 `_) +* Always trigger guard condition waitset (`#1923 `_) +* Add statistics for handle_loaned_message (`#1927 `_) +* Drop wrong template specialization (`#1926 `_) +* Contributors: Alberto Soragna, Andrew Symington, Barry Xu, Brian, Chen Lihui, Chris Lalancette, Daniel Reuter, Deepanshu Bansal, Hubert Liberacki, Ivan Santiago Paunovic, Jochen Sprickerhof, Nikolai Morin, Shane Loretz, Tomoya Fujita, Tyler Weaver, William Woodall, schrodinbug + 16.2.0 (2022-05-03) ------------------- * Update get_parameter_from_event to follow the function description (`#1922 `_) diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index 9572f422a8..3abd999f3d 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -259,4 +259,8 @@ if(TEST cppcheck) set_tests_properties(cppcheck PROPERTIES TIMEOUT 500) endif() +if(TEST cpplint) + set_tests_properties(cpplint PROPERTIES TIMEOUT 180) +endif() + ament_generate_version_header(${PROJECT_NAME}) diff --git a/rclcpp/doc/param_callback_design.png b/rclcpp/doc/param_callback_design.png new file mode 100644 index 0000000000..485b5b9532 Binary files /dev/null and b/rclcpp/doc/param_callback_design.png differ diff --git a/rclcpp/doc/proposed_node_parameter_callbacks.md b/rclcpp/doc/proposed_node_parameter_callbacks.md new file mode 100644 index 0000000000..cd39f352db --- /dev/null +++ b/rclcpp/doc/proposed_node_parameter_callbacks.md @@ -0,0 +1,29 @@ +# Proposed node parameters callback Design + +## Introduction: + +The original requirement came in **gazebo_ros_pkgs** for setting individual wheel slip parameters based on global wheel slip value [link to original issue](https://github.com/ros-simulation/gazebo_ros_pkgs/pull/1365). + +The main requirement is to set one or more parameters after another parameter is set successfully. + +Additionally, it would be nice if users could be notified locally (via a callback) when parameters have been set successfully (i.e. post validation). + +Related discussion can be found in [#609](https://github.com/ros2/rclcpp/issues/609) [#1789](https://github.com/ros2/rclcpp/pull/1789) + +With the current parameters API, the `add_on_set_parameters_callback` is intended for validation of parameter values before they are set, it should **not** cause any side-effects. + +There is also the `ParameterEventHandler` that publishes changes to node parameters on `/parameter_events` topic for external nodes to see. Though the node could subscribe to the `/parameter_events` topic to be notified of changes to its own parameters, it is less than ideal since there is a delay caused by waiting for an executor to process the callback. + +We propose adding a `PostSetParametersCallbackHandle` for successful parameter set similar to `OnSetParametersCallbackHandle` for parameter validation. Also, we propose adding a `PreSetParametersCallbackHandle` useful for modifying list of parameters being set. + +The validation callback is often abused to trigger side effects in the code, for instance updating class attributes even before a parameter has been set successfully. Instead of relying on the `/parameter_events` topic to be notified of parameter changes, users can register a callback with a new API, `add_post_set_parameters_callback`. + +It is possible to use the proposed `add_post_set_parameters_callback` for setting additional parameters, but this might result in infinite recursion and does not allow those additional parameters to be set atomically with the original parameter(s) changed. +To workaround these issues, we propose adding a "pre set" callback type that can be registered with `add_pre_set_parameters_callback`, which will be triggered before the validation callbacks and can be used to modify the parameter list. + +![Desgin API](https://github.com/ros2/rclcpp/blob/deepanshu/local-param-changed-callback-support/rclcpp/doc/param_callback_design.png?raw=true) + +## Alternatives + +* Users could call `set_parameter` while processing a message from the `/parameter_events` topic, however, there is extra overhead in having to create subscription (as noted earlier). +* Users could call `set_parameter` inside the "on set" parameters callback, however it is not well-defined how side-effects should handle cases where parameter validation fails. \ No newline at end of file diff --git a/rclcpp/include/rclcpp/allocator/allocator_common.hpp b/rclcpp/include/rclcpp/allocator/allocator_common.hpp index d117376517..12b2f383b6 100644 --- a/rclcpp/include/rclcpp/allocator/allocator_common.hpp +++ b/rclcpp/include/rclcpp/allocator/allocator_common.hpp @@ -15,6 +15,7 @@ #ifndef RCLCPP__ALLOCATOR__ALLOCATOR_COMMON_HPP_ #define RCLCPP__ALLOCATOR__ALLOCATOR_COMMON_HPP_ +#include #include #include "rcl/allocator.h" @@ -39,6 +40,22 @@ void * retyped_allocate(size_t size, void * untyped_allocator) return std::allocator_traits::allocate(*typed_allocator, size); } +template +void * retyped_zero_allocate(size_t number_of_elem, size_t size_of_elem, void * untyped_allocator) +{ + auto typed_allocator = static_cast(untyped_allocator); + if (!typed_allocator) { + throw std::runtime_error("Received incorrect allocator type"); + } + size_t size = number_of_elem * size_of_elem; + void * allocated_memory = + std::allocator_traits::allocate(*typed_allocator, size); + if (allocated_memory) { + std::memset(allocated_memory, 0, size); + } + return allocated_memory; +} + template void retyped_deallocate(void * untyped_pointer, void * untyped_allocator) { @@ -73,6 +90,7 @@ rcl_allocator_t get_rcl_allocator(Alloc & allocator) rcl_allocator_t rcl_allocator = rcl_get_default_allocator(); #ifndef _WIN32 rcl_allocator.allocate = &retyped_allocate; + rcl_allocator.zero_allocate = &retyped_zero_allocate; rcl_allocator.deallocate = &retyped_deallocate; rcl_allocator.reallocate = &retyped_reallocate; rcl_allocator.state = &allocator; diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index 94bceced81..7d03edf343 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -16,11 +16,14 @@ #define RCLCPP__CALLBACK_GROUP_HPP_ #include +#include +#include #include -#include #include #include "rclcpp/client.hpp" +#include "rclcpp/context.hpp" +#include "rclcpp/guard_condition.hpp" #include "rclcpp/publisher_base.hpp" #include "rclcpp/service.hpp" #include "rclcpp/subscription_base.hpp" @@ -95,6 +98,10 @@ class CallbackGroup CallbackGroupType group_type, bool automatically_add_to_executor_with_node = true); + /// Default destructor. + RCLCPP_PUBLIC + ~CallbackGroup(); + template rclcpp::SubscriptionBase::SharedPtr find_subscription_ptrs_if(Function func) const @@ -171,6 +178,16 @@ class CallbackGroup bool automatically_add_to_executor_with_node() const; + /// Defer creating the notify guard condition and return it. + RCLCPP_PUBLIC + rclcpp::GuardCondition::SharedPtr + get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr); + + /// Trigger the notify guard condition. + RCLCPP_PUBLIC + void + trigger_notify_guard_condition(); + protected: RCLCPP_DISABLE_COPY(CallbackGroup) @@ -213,6 +230,9 @@ class CallbackGroup std::vector waitable_ptrs_; std::atomic_bool can_be_taken_from_; const bool automatically_add_to_executor_with_node_; + // defer the creation of the guard condition + std::shared_ptr notify_guard_condition_ = nullptr; + std::recursive_mutex notify_guard_condition_mutex_; private: template diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 9b1522399c..1265f60c31 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -130,7 +130,7 @@ class ClientBase rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph); RCLCPP_PUBLIC - virtual ~ClientBase(); + virtual ~ClientBase() = default; /// Take the next response for this client as a type erased pointer. /** @@ -312,7 +312,7 @@ class ClientBase // This two-step setting, prevents a gap where the old std::function has // been replaced but the middleware hasn't been told about the new one yet. set_on_new_response_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline, static_cast(&new_callback)); // Store the std::function to keep it in scope, also overwrites the existing one. @@ -320,7 +320,8 @@ class ClientBase // Set it again, now using the permanent storage. set_on_new_response_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline< + decltype(on_new_response_callback_), const void *, size_t>, static_cast(&on_new_response_callback_)); } @@ -769,7 +770,9 @@ class Client : public ClientBase auto old_size = pending_requests_.size(); for (auto it = pending_requests_.begin(), last = pending_requests_.end(); it != last; ) { if (it->second.first < time_point) { - pruned_requests->push_back(it->first); + if (pruned_requests) { + pruned_requests->push_back(it->first); + } it = pending_requests_.erase(it); } else { ++it; @@ -792,16 +795,14 @@ class Client : public ClientBase async_send_request_impl(const Request & request, CallbackInfoVariant value) { int64_t sequence_number; + std::lock_guard lock(pending_requests_mutex_); rcl_ret_t ret = rcl_send_request(get_client_handle().get(), &request, &sequence_number); if (RCL_RET_OK != ret) { rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request"); } - { - std::lock_guard lock(pending_requests_mutex_); - pending_requests_.try_emplace( - sequence_number, - std::make_pair(std::chrono::system_clock::now(), std::move(value))); - } + pending_requests_.try_emplace( + sequence_number, + std::make_pair(std::chrono::system_clock::now(), std::move(value))); return sequence_number; } diff --git a/rclcpp/include/rclcpp/clock.hpp b/rclcpp/include/rclcpp/clock.hpp index 42d3e01e7e..702b224d53 100644 --- a/rclcpp/include/rclcpp/clock.hpp +++ b/rclcpp/include/rclcpp/clock.hpp @@ -77,7 +77,7 @@ class Clock */ RCLCPP_PUBLIC Time - now(); + now() const; /** * Sleep until a specified Time, according to clock type. @@ -137,6 +137,51 @@ class Clock Duration rel_time, Context::SharedPtr context = contexts::get_global_default_context()); + /** + * Check if the clock is started. + * + * A started clock is a clock that reflects non-zero time. + * Typically a clock will be unstarted if it is using RCL_ROS_TIME with ROS time and + * nothing has been published on the clock topic yet. + * + * \return true if clock is started + * \throws std::runtime_error if the clock is not rcl_clock_valid + */ + RCLCPP_PUBLIC + bool + started(); + + /** + * Wait until clock to start. + * + * \rclcpp::Clock::started + * \param context the context to wait in + * \return true if clock was already started or became started + * \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid + */ + RCLCPP_PUBLIC + bool + wait_until_started(Context::SharedPtr context = contexts::get_global_default_context()); + + /** + * Wait for clock to start, with timeout. + * + * The timeout is waited in steady time. + * + * \rclcpp::Clock::started + * \param timeout the maximum time to wait for. + * \param context the context to wait in. + * \param wait_tick_ns the time to wait between each iteration of the wait loop (in nanoseconds). + * \return true if clock was or became valid + * \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid + */ + RCLCPP_PUBLIC + bool + wait_until_started( + const rclcpp::Duration & timeout, + Context::SharedPtr context = contexts::get_global_default_context(), + const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast(1e7))); + /** * Returns the clock of the type `RCL_ROS_TIME` is active. * diff --git a/rclcpp/include/rclcpp/context.hpp b/rclcpp/include/rclcpp/context.hpp index 3add3f6d46..2917ce3363 100644 --- a/rclcpp/include/rclcpp/context.hpp +++ b/rclcpp/include/rclcpp/context.hpp @@ -398,20 +398,22 @@ class Context : public std::enable_shared_from_this using ShutdownCallback = ShutdownCallbackHandle::ShutdownCallbackType; + template RCLCPP_LOCAL ShutdownCallbackHandle add_shutdown_callback( - ShutdownType shutdown_type, ShutdownCallback callback); + template RCLCPP_LOCAL bool remove_shutdown_callback( - ShutdownType shutdown_type, const ShutdownCallbackHandle & callback_handle); + template + RCLCPP_LOCAL std::vector - get_shutdown_callback(ShutdownType shutdown_type) const; + get_shutdown_callback() const; }; /// Return a copy of the list of context shared pointers. diff --git a/rclcpp/include/rclcpp/create_client.hpp b/rclcpp/include/rclcpp/create_client.hpp index 1a960b8d8f..00e6ff3c0e 100644 --- a/rclcpp/include/rclcpp/create_client.hpp +++ b/rclcpp/include/rclcpp/create_client.hpp @@ -20,10 +20,40 @@ #include "rclcpp/node_interfaces/node_base_interface.hpp" #include "rclcpp/node_interfaces/node_services_interface.hpp" +#include "rclcpp/qos.hpp" #include "rmw/rmw.h" namespace rclcpp { +/// Create a service client with a given type. +/** + * \param[in] node_base NodeBaseInterface implementation of the node on which + * to create the client. + * \param[in] node_graph NodeGraphInterface implementation of the node on which + * to create the client. + * \param[in] node_services NodeServicesInterface implementation of the node on + * which to create the client. + * \param[in] service_name The name on which the service is accessible. + * \param[in] qos Quality of service profile for client. + * \param[in] group Callback group to handle the reply to service calls. + * \return Shared pointer to the created client. + */ +template +typename rclcpp::Client::SharedPtr +create_client( + std::shared_ptr node_base, + std::shared_ptr node_graph, + std::shared_ptr node_services, + const std::string & service_name, + const rclcpp::QoS & qos = rclcpp::ServicesQoS(), + rclcpp::CallbackGroup::SharedPtr group = nullptr) +{ + return create_client( + node_base, node_graph, node_services, + service_name, + qos.get_rmw_qos_profile(), + group); +} /// Create a service client with a given type. /// \internal diff --git a/rclcpp/include/rclcpp/create_service.hpp b/rclcpp/include/rclcpp/create_service.hpp index 9aaa02a1ed..42c253a526 100644 --- a/rclcpp/include/rclcpp/create_service.hpp +++ b/rclcpp/include/rclcpp/create_service.hpp @@ -26,6 +26,32 @@ namespace rclcpp { +/// Create a service with a given type. +/** + * \param[in] node_base NodeBaseInterface implementation of the node on which + * to create the service. + * \param[in] node_services NodeServicesInterface implementation of the node on + * which to create the service. + * \param[in] service_name The name on which the service is accessible. + * \param[in] callback The callback to call when the service gets a request. + * \param[in] qos Quality of service profile for the service. + * \param[in] group Callback group to handle the reply to service calls. + * \return Shared pointer to the created service. + */ +template +typename rclcpp::Service::SharedPtr +create_service( + std::shared_ptr node_base, + std::shared_ptr node_services, + const std::string & service_name, + CallbackT && callback, + const rclcpp::QoS & qos, + rclcpp::CallbackGroup::SharedPtr group) +{ + return create_service( + node_base, node_services, service_name, + std::forward(callback), qos.get_rmw_qos_profile(), group); +} /// Create a service with a given type. /// \internal diff --git a/rclcpp/include/rclcpp/create_timer.hpp b/rclcpp/include/rclcpp/create_timer.hpp index 345f43fcbb..d371466f0d 100644 --- a/rclcpp/include/rclcpp/create_timer.hpp +++ b/rclcpp/include/rclcpp/create_timer.hpp @@ -23,12 +23,63 @@ #include "rclcpp/duration.hpp" #include "rclcpp/node_interfaces/get_node_base_interface.hpp" +#include "rclcpp/node_interfaces/get_node_clock_interface.hpp" #include "rclcpp/node_interfaces/get_node_timers_interface.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" +#include "rclcpp/node_interfaces/node_clock_interface.hpp" #include "rclcpp/node_interfaces/node_timers_interface.hpp" namespace rclcpp { +namespace detail +{ +/// Perform a safe cast to a timer period in nanoseconds +/** + * + * \tparam DurationRepT + * \tparam DurationT + * \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max() + * \return period, expressed as chrono::duration::nanoseconds + * \throws std::invalid_argument if period is negative or too large + */ +template +std::chrono::nanoseconds +safe_cast_to_period_in_ns(std::chrono::duration period) +{ + if (period < std::chrono::duration::zero()) { + throw std::invalid_argument{"timer period cannot be negative"}; + } + + // Casting to a double representation might lose precision and allow the check below to succeed + // but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max. + constexpr auto maximum_safe_cast_ns = + std::chrono::nanoseconds::max() - std::chrono::duration(1); + + // If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow + // a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is + // greater than nanoseconds::max() is a difficult general problem. This is a more conservative + // version of Howard Hinnant's (the guy>) response here: + // https://stackoverflow.com/a/44637334/2089061 + // However, this doesn't solve the issue for all possible duration types of period. + // Follow-up issue: https://github.com/ros2/rclcpp/issues/1177 + constexpr auto ns_max_as_double = + std::chrono::duration_cast>( + maximum_safe_cast_ns); + if (period > ns_max_as_double) { + throw std::invalid_argument{ + "timer period must be less than std::chrono::nanoseconds::max()"}; + } + + const auto period_ns = std::chrono::duration_cast(period); + if (period_ns < std::chrono::nanoseconds::zero()) { + throw std::runtime_error{ + "Casting timer period to nanoseconds resulted in integer overflow."}; + } + + return period_ns; +} +} // namespace detail + /// Create a timer with a given clock /// \internal template @@ -41,14 +92,13 @@ create_timer( CallbackT && callback, rclcpp::CallbackGroup::SharedPtr group = nullptr) { - auto timer = rclcpp::GenericTimer::make_shared( + return create_timer( clock, period.to_chrono(), std::forward(callback), - node_base->get_context()); - - node_timers->add_timer(timer, group); - return timer; + group, + node_base.get(), + node_timers.get()); } /// Create a timer with a given clock @@ -62,82 +112,99 @@ create_timer( rclcpp::CallbackGroup::SharedPtr group = nullptr) { return create_timer( - rclcpp::node_interfaces::get_node_base_interface(node), - rclcpp::node_interfaces::get_node_timers_interface(node), clock, - period, + period.to_chrono(), std::forward(callback), - group); + group, + rclcpp::node_interfaces::get_node_base_interface(node).get(), + rclcpp::node_interfaces::get_node_timers_interface(node).get()); } -/// Convenience method to create a timer with node resources. +/// Convenience method to create a general timer with node resources. /** * * \tparam DurationRepT * \tparam DurationT * \tparam CallbackT + * \param clock clock to be used * \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max() * \param callback callback to execute via the timer period - * \param group - * \param node_base - * \param node_timers - * \return - * \throws std::invalid argument if either node_base or node_timers - * are null, or period is negative or too large + * \param group callback group + * \param node_base node base interface + * \param node_timers node timer interface + * \return shared pointer to a generic timer + * \throws std::invalid_argument if either clock, node_base or node_timers + * are nullptr, or period is negative or too large */ template -typename rclcpp::WallTimer::SharedPtr -create_wall_timer( +typename rclcpp::GenericTimer::SharedPtr +create_timer( + rclcpp::Clock::SharedPtr clock, std::chrono::duration period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group, node_interfaces::NodeBaseInterface * node_base, node_interfaces::NodeTimersInterface * node_timers) { + if (clock == nullptr) { + throw std::invalid_argument{"clock cannot be null"}; + } if (node_base == nullptr) { throw std::invalid_argument{"input node_base cannot be null"}; } - if (node_timers == nullptr) { throw std::invalid_argument{"input node_timers cannot be null"}; } - if (period < std::chrono::duration::zero()) { - throw std::invalid_argument{"timer period cannot be negative"}; - } + const std::chrono::nanoseconds period_ns = detail::safe_cast_to_period_in_ns(period); - // Casting to a double representation might lose precision and allow the check below to succeed - // but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max. - constexpr auto maximum_safe_cast_ns = - std::chrono::nanoseconds::max() - std::chrono::duration(1); + // Add a new generic timer. + auto timer = rclcpp::GenericTimer::make_shared( + std::move(clock), period_ns, std::move(callback), node_base->get_context()); + node_timers->add_timer(timer, group); + return timer; +} - // If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow - // a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is - // greater than nanoseconds::max() is a difficult general problem. This is a more conservative - // version of Howard Hinnant's (the guy>) response here: - // https://stackoverflow.com/a/44637334/2089061 - // However, this doesn't solve the issue for all possible duration types of period. - // Follow-up issue: https://github.com/ros2/rclcpp/issues/1177 - constexpr auto ns_max_as_double = - std::chrono::duration_cast>( - maximum_safe_cast_ns); - if (period > ns_max_as_double) { - throw std::invalid_argument{ - "timer period must be less than std::chrono::nanoseconds::max()"}; +/// Convenience method to create a wall timer with node resources. +/** + * + * \tparam DurationRepT + * \tparam DurationT + * \tparam CallbackT + * \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max() + * \param callback callback to execute via the timer period + * \param group callback group + * \param node_base node base interface + * \param node_timers node timer interface + * \return shared pointer to a wall timer + * \throws std::invalid_argument if either node_base or node_timers + * are null, or period is negative or too large + */ +template +typename rclcpp::WallTimer::SharedPtr +create_wall_timer( + std::chrono::duration period, + CallbackT callback, + rclcpp::CallbackGroup::SharedPtr group, + node_interfaces::NodeBaseInterface * node_base, + node_interfaces::NodeTimersInterface * node_timers) +{ + if (node_base == nullptr) { + throw std::invalid_argument{"input node_base cannot be null"}; } - const auto period_ns = std::chrono::duration_cast(period); - if (period_ns < std::chrono::nanoseconds::zero()) { - throw std::runtime_error{ - "Casting timer period to nanoseconds resulted in integer overflow."}; + if (node_timers == nullptr) { + throw std::invalid_argument{"input node_timers cannot be null"}; } + const std::chrono::nanoseconds period_ns = detail::safe_cast_to_period_in_ns(period); + + // Add a new wall timer. auto timer = rclcpp::WallTimer::make_shared( period_ns, std::move(callback), node_base->get_context()); node_timers->add_timer(timer, group); return timer; } - } // namespace rclcpp #endif // RCLCPP__CREATE_TIMER_HPP_ diff --git a/rclcpp/include/rclcpp/detail/cpp_callback_trampoline.hpp b/rclcpp/include/rclcpp/detail/cpp_callback_trampoline.hpp index 4f46dfc939..e9c07b71e0 100644 --- a/rclcpp/include/rclcpp/detail/cpp_callback_trampoline.hpp +++ b/rclcpp/include/rclcpp/detail/cpp_callback_trampoline.hpp @@ -41,6 +41,7 @@ namespace detail * so no exceptions should be thrown at this point, and doing so results in * undefined behavior. * + * \tparam UserDataRealT Declared type of the passed function * \tparam UserDataT Deduced type based on what is passed for user data, * usually this type is either `void *` or `const void *`. * \tparam Args the arguments being passed to the callback @@ -50,6 +51,7 @@ namespace detail * \returns whatever the callback returns, if anything */ template< + typename UserDataRealT, typename UserDataT, typename ... Args, typename ReturnT = void @@ -57,7 +59,7 @@ template< ReturnT cpp_callback_trampoline(UserDataT user_data, Args ... args) noexcept { - auto & actual_callback = *reinterpret_cast *>(user_data); + auto & actual_callback = *static_cast(user_data); return actual_callback(args ...); } diff --git a/rclcpp/include/rclcpp/detail/template_contains.hpp b/rclcpp/include/rclcpp/detail/template_contains.hpp new file mode 100644 index 0000000000..b60a75f36d --- /dev/null +++ b/rclcpp/include/rclcpp/detail/template_contains.hpp @@ -0,0 +1,47 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP__DETAIL__TEMPLATE_CONTAINS_HPP_ +#define RCLCPP__DETAIL__TEMPLATE_CONTAINS_HPP_ + +#include + +namespace rclcpp +{ +namespace detail +{ + +/// Template meta-function that checks if a given T is contained in the list Us. +template +struct template_contains; + +template +inline constexpr bool template_contains_v = template_contains::value; + +template +struct template_contains +{ + enum { value = (std::is_same_v|| template_contains_v)}; +}; + +template +struct template_contains +{ + enum { value = false }; +}; + +} // namespace detail +} // namespace rclcpp + +#endif // RCLCPP__DETAIL__TEMPLATE_CONTAINS_HPP_ diff --git a/rclcpp/include/rclcpp/detail/template_unique.hpp b/rclcpp/include/rclcpp/detail/template_unique.hpp new file mode 100644 index 0000000000..4986102d78 --- /dev/null +++ b/rclcpp/include/rclcpp/detail/template_unique.hpp @@ -0,0 +1,49 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP__DETAIL__TEMPLATE_UNIQUE_HPP_ +#define RCLCPP__DETAIL__TEMPLATE_UNIQUE_HPP_ + +#include + +#include "rclcpp/detail/template_contains.hpp" + +namespace rclcpp +{ +namespace detail +{ + +/// Template meta-function that checks if a given list Ts contains unique types. +template +struct template_unique; + +template +inline constexpr bool template_unique_v = template_unique::value; + +template +struct template_unique +{ + enum { value = !template_contains_v&& template_unique_v}; +}; + +template +struct template_unique +{ + enum { value = true }; +}; + +} // namespace detail +} // namespace rclcpp + +#endif // RCLCPP__DETAIL__TEMPLATE_UNIQUE_HPP_ diff --git a/rclcpp/include/rclcpp/duration.hpp b/rclcpp/include/rclcpp/duration.hpp index 28b3718660..537e2a9bf6 100644 --- a/rclcpp/include/rclcpp/duration.hpp +++ b/rclcpp/include/rclcpp/duration.hpp @@ -92,9 +92,13 @@ class RCLCPP_PUBLIC Duration Duration operator+(const rclcpp::Duration & rhs) const; + Duration & operator+=(const rclcpp::Duration & rhs); + Duration operator-(const rclcpp::Duration & rhs) const; + Duration & operator-=(const rclcpp::Duration & rhs); + /// Get the maximum representable value. /** * \return the maximum representable value @@ -106,6 +110,9 @@ class RCLCPP_PUBLIC Duration Duration operator*(double scale) const; + Duration & + operator*=(double scale); + /// Get duration in nanosecods /** * \return the duration in nanoseconds as a rcl_duration_value_t. diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index a700b8f454..102d044045 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -611,14 +611,14 @@ class Executor } public: - typedef std::map> - WeakNodesToGuardConditionsMap; + std::owner_less> + WeakCallbackGroupsToGuardConditionsMap; - /// maps nodes to guard conditions - WeakNodesToGuardConditionsMap - weak_nodes_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_); + /// maps callback groups to guard conditions + WeakCallbackGroupsToGuardConditionsMap + weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_); /// maps callback groups associated to nodes WeakCallbackGroupsToNodesMap diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index c1de8051f2..119013ebfb 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -47,7 +47,7 @@ class MultiThreadedExecutor : public rclcpp::Executor * * \param options common options for all executors * \param number_of_threads number of threads to have in the thread pool, - * the default 0 will use the number of cpu cores found instead + * the default 0 will use the number of cpu cores found (minimum of 2) * \param yield_before_execute if true std::this_thread::yield() is called * \param timeout maximum time to wait */ diff --git a/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp b/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp index c01240b429..245d417d86 100644 --- a/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp +++ b/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp @@ -86,8 +86,7 @@ class RingBufferImplementation : public BufferImplementationBase std::lock_guard lock(mutex_); if (!has_data_()) { - RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Calling dequeue on empty intra-process buffer"); - throw std::runtime_error("Calling dequeue on empty intra-process buffer"); + return BufferT(); } auto request = std::move(ring_buffer_[read_index_]); diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp index 803d940086..91ea91a7c3 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp @@ -109,8 +109,14 @@ class SubscriptionIntraProcess if (any_callback_.use_take_shared_method()) { shared_msg = this->buffer_->consume_shared(); + if (!shared_msg) { + return nullptr; + } } else { unique_msg = this->buffer_->consume_unique(); + if (!unique_msg) { + return nullptr; + } } return std::static_pointer_cast( std::make_shared>( @@ -138,7 +144,7 @@ class SubscriptionIntraProcess execute_impl(std::shared_ptr & data) { if (!data) { - throw std::runtime_error("'data' is empty"); + return; } rmw_message_info_t msg_info; diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp index 037d1aaa2a..6583e74ae7 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp @@ -52,7 +52,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable {} RCLCPP_PUBLIC - virtual ~SubscriptionIntraProcessBase(); + virtual ~SubscriptionIntraProcessBase() = default; RCLCPP_PUBLIC size_t diff --git a/rclcpp/include/rclcpp/generic_publisher.hpp b/rclcpp/include/rclcpp/generic_publisher.hpp index e1b46002bc..7cd2d8bc39 100644 --- a/rclcpp/include/rclcpp/generic_publisher.hpp +++ b/rclcpp/include/rclcpp/generic_publisher.hpp @@ -78,38 +78,12 @@ class GenericPublisher : public rclcpp::PublisherBase node_base, topic_name, *rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib), - options.template to_rcl_publisher_options(qos)), + options.template to_rcl_publisher_options(qos), + // NOTE(methylDragon): Passing these args separately is necessary for event binding + options.event_callbacks, + options.use_default_callbacks), ts_lib_(ts_lib) - { - // This is unfortunately duplicated with the code in publisher.hpp. - // TODO(nnmm): Deduplicate by moving this into PublisherBase. - if (options.event_callbacks.deadline_callback) { - this->add_event_handler( - options.event_callbacks.deadline_callback, - RCL_PUBLISHER_OFFERED_DEADLINE_MISSED); - } - if (options.event_callbacks.liveliness_callback) { - this->add_event_handler( - options.event_callbacks.liveliness_callback, - RCL_PUBLISHER_LIVELINESS_LOST); - } - if (options.event_callbacks.incompatible_qos_callback) { - this->add_event_handler( - options.event_callbacks.incompatible_qos_callback, - RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS); - } else if (options.use_default_callbacks) { - // Register default callback when not specified - try { - this->add_event_handler( - [this](QOSOfferedIncompatibleQoSInfo & info) { - this->default_incompatible_qos_callback(info); - }, - RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS); - } catch (UnsupportedEventTypeException & /*exc*/) { - // pass - } - } - } + {} RCLCPP_PUBLIC virtual ~GenericPublisher() = default; diff --git a/rclcpp/include/rclcpp/generic_subscription.hpp b/rclcpp/include/rclcpp/generic_subscription.hpp index 673712eedb..12a1c79f8f 100644 --- a/rclcpp/include/rclcpp/generic_subscription.hpp +++ b/rclcpp/include/rclcpp/generic_subscription.hpp @@ -81,45 +81,13 @@ class GenericSubscription : public rclcpp::SubscriptionBase node_base, *rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib), topic_name, - options.template to_rcl_subscription_options(qos), + options.to_rcl_subscription_options(qos), + options.event_callbacks, + options.use_default_callbacks, true), callback_(callback), ts_lib_(ts_lib) - { - // This is unfortunately duplicated with the code in subscription.hpp. - // TODO(nnmm): Deduplicate by moving this into SubscriptionBase. - if (options.event_callbacks.deadline_callback) { - this->add_event_handler( - options.event_callbacks.deadline_callback, - RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED); - } - if (options.event_callbacks.liveliness_callback) { - this->add_event_handler( - options.event_callbacks.liveliness_callback, - RCL_SUBSCRIPTION_LIVELINESS_CHANGED); - } - if (options.event_callbacks.incompatible_qos_callback) { - this->add_event_handler( - options.event_callbacks.incompatible_qos_callback, - RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS); - } else if (options.use_default_callbacks) { - // Register default callback when not specified - try { - this->add_event_handler( - [this](QOSRequestedIncompatibleQoSInfo & info) { - this->default_incompatible_qos_callback(info); - }, - RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS); - } catch (UnsupportedEventTypeException & /*exc*/) { - // pass - } - } - if (options.event_callbacks.message_lost_callback) { - this->add_event_handler( - options.event_callbacks.message_lost_callback, - RCL_SUBSCRIPTION_MESSAGE_LOST); - } - } + {} RCLCPP_PUBLIC virtual ~GenericSubscription() = default; diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 65b8797716..7ecb67e9b1 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -227,7 +227,7 @@ class Node : public std::enable_shared_from_this ) ); - /// Create a timer. + /// Create a wall timer that uses the wall clock to drive the callback. /** * \param[in] period Time interval between triggers of the callback. * \param[in] callback User-defined callback function. @@ -240,18 +240,47 @@ class Node : public std::enable_shared_from_this CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr); + /// Create a timer that uses the node clock to drive the callback. + /** + * \param[in] period Time interval between triggers of the callback. + * \param[in] callback User-defined callback function. + * \param[in] group Callback group to execute this timer's callback in. + */ + template + typename rclcpp::GenericTimer::SharedPtr + create_timer( + std::chrono::duration period, + CallbackT callback, + rclcpp::CallbackGroup::SharedPtr group = nullptr); + /// Create and return a Client. /** * \param[in] service_name The topic to service on. * \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client. * \param[in] group Callback group to call the service. * \return Shared pointer to the created client. + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + typename rclcpp::Client::SharedPtr + create_client( + const std::string & service_name, + const rmw_qos_profile_t & qos_profile, + rclcpp::CallbackGroup::SharedPtr group = nullptr); + + /// Create and return a Client. + /** + * \param[in] service_name The name on which the service is accessible. + * \param[in] qos Quality of service profile for client. + * \param[in] group Callback group to handle the reply to service calls. + * \return Shared pointer to the created client. */ template typename rclcpp::Client::SharedPtr create_client( const std::string & service_name, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, + const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Create and return a Service. @@ -261,13 +290,31 @@ class Node : public std::enable_shared_from_this * \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client. * \param[in] group Callback group to call the service. * \return Shared pointer to the created service. + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + typename rclcpp::Service::SharedPtr + create_service( + const std::string & service_name, + CallbackT && callback, + const rmw_qos_profile_t & qos_profile, + rclcpp::CallbackGroup::SharedPtr group = nullptr); + + /// Create and return a Service. + /** + * \param[in] service_name The topic to service on. + * \param[in] callback User-defined callback function. + * \param[in] qos Quality of service profile for the service. + * \param[in] group Callback group to call the service. + * \return Shared pointer to the created service. */ template typename rclcpp::Service::SharedPtr create_service( const std::string & service_name, CallbackT && callback, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, + const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Create and return a GenericPublisher. @@ -336,11 +383,21 @@ class Node : public std::enable_shared_from_this * * If `ignore_override` is `true`, the parameter override will be ignored. * - * This method, if successful, will result in any callback registered with - * add_on_set_parameters_callback to be called. + * This method will result in any callback registered with + * `add_on_set_parameters_callback` and `add_post_set_parameters_callback` + * to be called for the parameter being set. + * + * If a callback was registered previously with `add_on_set_parameters_callback`, + * it will be called prior to setting the parameter for the node. * If that callback prevents the initial value for the parameter from being * set then rclcpp::exceptions::InvalidParameterValueException is thrown. * + * If a callback was registered previously with `add_post_set_parameters_callback`, + * it will be called after setting the parameter successfully for the node. + * + * This method will _not_ result in any callbacks registered with + * `add_pre_set_parameters_callback` to be called. + * * The returned reference will remain valid until the parameter is * undeclared. * @@ -457,11 +514,22 @@ class Node : public std::enable_shared_from_this * If `ignore_overrides` is `true`, all the overrides of the parameters declared * by the function call will be ignored. * + * This method will result in any callback registered with + * `add_on_set_parameters_callback` and `add_post_set_parameters_callback` + * to be called once for each parameter. + * * This method, if successful, will result in any callback registered with - * add_on_set_parameters_callback to be called, once for each parameter. + * `add_on_set_parameters_callback` to be called, once for each parameter. * If that callback prevents the initial value for any parameter from being * set then rclcpp::exceptions::InvalidParameterValueException is thrown. * + * If a callback was registered previously with `add_post_set_parameters_callback`, + * it will be called after setting the parameters successfully for the node, + * once for each parameter. + * + * This method will _not_ result in any callbacks registered with + * `add_pre_set_parameters_callback` to be called. + * * \param[in] namespace_ The namespace in which to declare the parameters. * \param[in] parameters The parameters to set in the given namespace. * \param[in] ignore_overrides When `true`, the parameters overrides are ignored. @@ -499,8 +567,9 @@ class Node : public std::enable_shared_from_this /// Undeclare a previously declared parameter. /** - * This method will not cause a callback registered with - * add_on_set_parameters_callback to be called. + * This method will _not_ cause a callback registered with any of the + * `add_pre_set_parameters_callback`, `add_on_set_parameters_callback` and + * `add_post_set_parameters_callback` to be called. * * \param[in] name The name of the parameter to be undeclared. * \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter @@ -534,11 +603,24 @@ class Node : public std::enable_shared_from_this * Parameter overrides are ignored by set_parameter. * * This method will result in any callback registered with - * add_on_set_parameters_callback to be called. + * `add_pre_set_parameters_callback`, add_on_set_parameters_callback` and + * `add_post_set_parameters_callback` to be called once for the parameter + * being set. + * + * This method will result in any callback registered with + * `add_on_set_parameters_callback` to be called. * If the callback prevents the parameter from being set, then it will be * reflected in the SetParametersResult that is returned, but no exception * will be thrown. * + * If a callback was registered previously with `add_pre_set_parameters_callback`, + * it will be called once prior to the validation of the parameter for the node. + * If this callback makes modified parameter list empty, then it will be reflected + * in the returned result; no exceptions will be raised in this case. + * + * If a callback was registered previously with `add_post_set_parameters_callback`, + * it will be called once after setting the parameter successfully for the node. + * * If the value type of the parameter is rclcpp::PARAMETER_NOT_SET, and the * existing parameter type is something else, then the parameter will be * implicitly undeclared. @@ -575,11 +657,25 @@ class Node : public std::enable_shared_from_this * corresponding SetParametersResult in the vector returned by this function. * * This method will result in any callback registered with - * add_on_set_parameters_callback to be called, once for each parameter. + * `add_pre_set_parameters_callback`, `add_on_set_parameters_callback` and + * `add_post_set_parameters_callback` to be called once for each parameter. + + * If a callback was registered previously with `add_pre_set_parameters_callback`, + * it will be called prior to the validation of parameters for the node, + * once for each parameter. + * If this callback makes modified parameter list empty, then it will be reflected + * in the returned result; no exceptions will be raised in this case. + * + * This method will result in any callback registered with + * `add_on_set_parameters_callback` to be called, once for each parameter. * If the callback prevents the parameter from being set, then, as mentioned * before, it will be reflected in the corresponding SetParametersResult * that is returned, but no exception will be thrown. * + * If a callback was registered previously with `add_post_set_parameters_callback`, + * it will be called after setting the parameters successfully for the node, + * once for each parameter. + * * Like set_parameter() this method will implicitly undeclare parameters * with the type rclcpp::PARAMETER_NOT_SET. * @@ -606,11 +702,25 @@ class Node : public std::enable_shared_from_this * If the exception is thrown then none of the parameters will have been set. * * This method will result in any callback registered with - * add_on_set_parameters_callback to be called, just one time. + * `add_pre_set_parameters_callback`, `add_on_set_parameters_callback` and + * `add_post_set_parameters_callback` to be called only 'once' for all parameters. + * + * If a callback was registered previously with `add_pre_set_parameters_callback`, + * it will be called prior to the validation of node parameters, just one time + * for all parameters. + * If this callback makes modified parameter list empty, then it will be reflected + * in the returned result; no exceptions will be raised in this case. + * + * This method will result in any callback registered with + * 'add_on_set_parameters_callback' to be called, just one time. * If the callback prevents the parameters from being set, then it will be * reflected in the SetParametersResult which is returned, but no exception * will be thrown. * + * If a callback was registered previously with `add_post_set_parameters_callback`, + * it will be called after setting the node parameters successfully, just one time + * for all parameters. + * * If you pass multiple rclcpp::Parameter instances with the same name, then * only the last one in the vector (forward iteration) will be set. * @@ -630,17 +740,21 @@ class Node : public std::enable_shared_from_this /** * If the parameter has not been declared, then this method may throw the * rclcpp::exceptions::ParameterNotDeclaredException exception. + * If the parameter has not been initialized, then this method may throw the + * rclcpp::exceptions::ParameterUninitializedException exception. * * If undeclared parameters are allowed, see the node option * rclcpp::NodeOptions::allow_undeclared_parameters, then this method will - * not throw an exception, and instead return a default initialized - * rclcpp::Parameter, which has a type of + * not throw the rclcpp::exceptions::ParameterNotDeclaredException exception, + * and instead return a default initialized rclcpp::Parameter, which has a type of * rclcpp::ParameterType::PARAMETER_NOT_SET. * * \param[in] name The name of the parameter to get. * \return The requested parameter inside of a rclcpp parameter object. * \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter * has not been declared and undeclared parameters are not allowed. + * \throws rclcpp::exceptions::ParameterUninitializedException if the parameter + * has not been initialized. */ RCLCPP_PUBLIC rclcpp::Parameter @@ -724,12 +838,12 @@ class Node : public std::enable_shared_from_this /// Return the parameters by the given parameter names. /** - * Like get_parameters(), this method may throw the + * Like get_parameter(const std::string &), this method may throw the * rclcpp::exceptions::ParameterNotDeclaredException exception if the * requested parameter has not been declared and undeclared parameters are - * not allowed. + * not allowed, and may throw the rclcpp::exceptions::ParameterUninitializedException exception. * - * Also like get_parameters(), if undeclared parameters are allowed and the + * Also like get_parameter(const std::string &), if undeclared parameters are allowed and the * parameter has not been declared, then the corresponding rclcpp::Parameter * will be default initialized and therefore have the type * rclcpp::ParameterType::PARAMETER_NOT_SET. @@ -739,6 +853,8 @@ class Node : public std::enable_shared_from_this * \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the * parameters have not been declared and undeclared parameters are not * allowed. + * \throws rclcpp::exceptions::ParameterUninitializedException if any of the + * parameters have not been initialized. */ RCLCPP_PUBLIC std::vector @@ -859,12 +975,85 @@ class Node : public std::enable_shared_from_this rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const; + using PreSetParametersCallbackHandle = + rclcpp::node_interfaces::PreSetParametersCallbackHandle; + using PreSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType; + using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle; - using OnParametersSetCallbackType = - rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType; + using OnSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType; + using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] = + OnSetParametersCallbackType; + + using PostSetParametersCallbackHandle = + rclcpp::node_interfaces::PostSetParametersCallbackHandle; + using PostSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType; + + /// Add a callback that gets triggered before parameters are validated. + /** + * This callback can be used to modify the original list of parameters being + * set by the user. + * + * The modified list of parameters is then forwarded to the "on set parameter" + * callback for validation. + * + * The callback is called whenever any of the `set_parameter*` methods are called + * or when a set parameter service request is received. + * + * The callback takes a reference to the vector of parameters to be set. + * + * The vector of parameters may be modified by the callback. + * + * One of the use case of "pre set callback" can be updating additional parameters + * conditioned on changes to a parameter. + * + * Users should retain a copy of the returned shared pointer, as the callback + * is valid only as long as the smart pointer is alive. + * + * For an example callback: + * + *```cpp + * void + * preSetParameterCallback(std::vector & parameters) + * { + * for (auto & param : parameters) { + * if (param.get_name() == "param1") { + * parameters.push_back(rclcpp::Parameter("param2", 4.0)); + * } + * } + * } + * ``` + * The above callback appends 'param2' to the list of parameters to be set if + * 'param1' is being set by the user. + * + * All parameters in the vector will be set atomically. + * + * Note that the callback is only called while setting parameters with `set_parameter`, + * `set_parameters`, `set_parameters_atomically`, or externally with a parameters service. + * + * The callback is not called when parameters are declared with `declare_parameter` + * or `declare_parameters`. + * + * The callback is not called when parameters are undeclared with `undeclare_parameter`. + * + * An empty modified parameter list from the callback will result in "set_parameter*" + * returning an unsuccessful result. + * + * The `remove_pre_set_parameters_callback` can be used to deregister the callback. + * + * \param callback The callback to register. + * \returns A shared pointer. The callback is valid as long as the smart pointer is alive. + * \throws std::bad_alloc if the allocation of the PreSetParametersCallbackHandle fails. + */ + RCLCPP_PUBLIC + RCUTILS_WARN_UNUSED + PreSetParametersCallbackHandle::SharedPtr + add_pre_set_parameters_callback(PreSetParametersCallbackType callback); - /// Add a callback for when parameters are being set. + /// Add a callback to validate parameters before they are set. /** * The callback signature is designed to allow handling of any of the above * `set_parameter*` or `declare_parameter*` methods, and so it takes a const @@ -872,6 +1061,9 @@ class Node : public std::enable_shared_from_this * rcl_interfaces::msg::SetParametersResult to indicate whether or not the * parameter should be set or not, and if not why. * + * Users should retain a copy of the returned shared pointer, as the callback + * is valid only as long as the smart pointer is alive. + * * For an example callback: * * ```cpp @@ -903,6 +1095,8 @@ class Node : public std::enable_shared_from_this * this callback, so when checking a new value against the existing one, you * must account for the case where the parameter is not yet set. * + * The callback is not called when parameters are undeclared with `undeclare_parameter`. + * * Some constraints like read_only are enforced before the callback is called. * * The callback may introspect other already set parameters (by calling any @@ -931,7 +1125,80 @@ class Node : public std::enable_shared_from_this RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr - add_on_set_parameters_callback(OnParametersSetCallbackType callback); + add_on_set_parameters_callback(OnSetParametersCallbackType callback); + + /// Add a callback that gets triggered after parameters are set successfully. + /** + * The callback is called when any of the `set_parameter*` or `declare_parameter*` + * methods are successful. + * + * Users should retain a copy of the returned shared pointer, as the callback + * is valid only as long as the smart pointer is alive. + * + * The callback takes a reference to a const vector of parameters that have been + * set successfully. + * + * The post callback can be valuable as a place to cause side-effects based on + * parameter changes. + * For instance updating internally tracked class attributes once parameters + * have been changed successfully. + * + * For an example callback: + * + * ```cpp + * void + * postSetParameterCallback(const std::vector & parameters) + * { + * for(const auto & param:parameters) { + * // the internal class member can be changed after + * // successful change to param1 or param2 + * if(param.get_name() == "param1") { + * internal_tracked_class_parameter_1_ = param.get_value(); + * } + * else if(param.get_name() == "param2") { + * internal_tracked_class_parameter_2_ = param.get_value(); + * } + * } + * } + * ``` + * + * The above callback takes a const reference to list of parameters that have been + * set successfully and as a result of this updates the internally tracked class attributes + * `internal_tracked_class_parameter_1_` and `internal_tracked_class_parameter_2_` + * respectively. + * + * This callback should not modify parameters. + * + * The callback is called when parameters are declared with `declare_parameter` + * or `declare_parameters`. See `declare_parameter` or `declare_parameters` above. + * + * The callback is not called when parameters are undeclared with `undeclare_parameter`. + * + * If you want to make changes to parameters based on changes to another, use + * `add_pre_set_parameters_callback`. + * + * The `remove_post_set_parameters_callback` can be used to deregister the callback. + * + * \param callback The callback to register. + * \returns A shared pointer. The callback is valid as long as the smart pointer is alive. + * \throws std::bad_alloc if the allocation of the OnSetParametersCallbackHandle fails. + */ + RCLCPP_PUBLIC + RCUTILS_WARN_UNUSED + PostSetParametersCallbackHandle::SharedPtr + add_post_set_parameters_callback(PostSetParametersCallbackType callback); + + /// Remove a callback registered with `add_pre_set_parameters_callback`. + /** + * Delete a handler returned by `add_pre_set_parameters_callback`. + * + * \param handler The callback handler to remove. + * \throws std::runtime_error if the handler was not created with `add_pre_set_parameters_callback`, + * or if it has been removed before. + */ + RCLCPP_PUBLIC + void + remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle * const handler); /// Remove a callback registered with `add_on_set_parameters_callback`. /** @@ -960,6 +1227,18 @@ class Node : public std::enable_shared_from_this void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler); + /// Remove a callback registered with `add_post_set_parameters_callback`. + /** + * Delete a handler returned by `add_post_set_parameters_callback`. + * + * \param handler The callback handler to remove. + * \throws std::runtime_error if the handler was not created with `add_post_set_parameters_callback`, + * or if it has been removed before. + */ + RCLCPP_PUBLIC + void + remove_post_set_parameters_callback(const PostSetParametersCallbackHandle * const handler); + /// Get the fully-qualified names of all available nodes. /** * The fully-qualified name includes the local namespace and name of the node. diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 086c2bb17c..d6b090d4d1 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -120,6 +120,38 @@ Node::create_wall_timer( this->node_timers_.get()); } +template +typename rclcpp::GenericTimer::SharedPtr +Node::create_timer( + std::chrono::duration period, + CallbackT callback, + rclcpp::CallbackGroup::SharedPtr group) +{ + return rclcpp::create_timer( + this->get_clock(), + period, + std::move(callback), + group, + this->node_base_.get(), + this->node_timers_.get()); +} + +template +typename Client::SharedPtr +Node::create_client( + const std::string & service_name, + const rclcpp::QoS & qos, + rclcpp::CallbackGroup::SharedPtr group) +{ + return rclcpp::create_client( + node_base_, + node_graph_, + node_services_, + extend_name_with_sub_namespace(service_name, this->get_sub_namespace()), + qos, + group); +} + template typename Client::SharedPtr Node::create_client( @@ -136,6 +168,23 @@ Node::create_client( group); } +template +typename rclcpp::Service::SharedPtr +Node::create_service( + const std::string & service_name, + CallbackT && callback, + const rclcpp::QoS & qos, + rclcpp::CallbackGroup::SharedPtr group) +{ + return rclcpp::create_service( + node_base_, + node_services_, + extend_name_with_sub_namespace(service_name, this->get_sub_namespace()), + std::forward(callback), + qos, + group); +} + template typename rclcpp::Service::SharedPtr Node::create_service( diff --git a/rclcpp/include/rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp b/rclcpp/include/rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp new file mode 100644 index 0000000000..8f7b452f5f --- /dev/null +++ b/rclcpp/include/rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp @@ -0,0 +1,204 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP__NODE_INTERFACES__DETAIL__NODE_INTERFACES_HELPERS_HPP_ +#define RCLCPP__NODE_INTERFACES__DETAIL__NODE_INTERFACES_HELPERS_HPP_ + +#include +#include +#include +#include + +#include "rclcpp/visibility_control.hpp" + +namespace rclcpp +{ +namespace node_interfaces +{ +namespace detail +{ + +// Support and Helper template classes for the NodeInterfaces class. + +template +std::tuple...> +init_tuple(NodeT & n); + +/// Stores the interfaces in a tuple, provides constructors, and getters. +template +struct NodeInterfacesStorage +{ + template + NodeInterfacesStorage(NodeT & node) // NOLINT(runtime/explicit) + : interfaces_(init_tuple(node)) + {} + + explicit NodeInterfacesStorage(std::shared_ptr... args) + : interfaces_(args ...) + {} + + /// Individual Node Interface non-const getter. + template + std::shared_ptr + get() + { + static_assert( + (std::is_same_v|| ...), + "NodeInterfaces class does not contain given NodeInterfaceT"); + return std::get>(interfaces_); + } + + /// Individual Node Interface const getter. + template + std::shared_ptr + get() const + { + static_assert( + (std::is_same_v|| ...), + "NodeInterfaces class does not contain given NodeInterfaceT"); + return std::get>(interfaces_); + } + +protected: + std::tuple...> interfaces_; +}; + +/// Prototype of NodeInterfacesSupports. +/** + * Should read NodeInterfacesSupports<..., T, ...> as "NodeInterfaces supports T", and + * if NodeInterfacesSupport is specialized for T, the is_supported should be + * set to std::true_type, but by default it is std::false_type, which will + * lead to a compiler error when trying to use T with NodeInterfaces. + */ +template +struct NodeInterfacesSupports; + +/// Prototype of NodeInterfacesSupportCheck template meta-function. +/** + * This meta-function checks that all the types given are supported, + * throwing a more human-readable error if an unsupported type is used. + */ +template +struct NodeInterfacesSupportCheck; + +/// Iterating specialization that ensures classes are supported and inherited. +template +struct NodeInterfacesSupportCheck + : public NodeInterfacesSupportCheck +{ + static_assert( + NodeInterfacesSupports::is_supported::value, + "given NodeInterfaceT is not supported by rclcpp::node_interfaces::NodeInterfaces"); +}; + +/// Terminating case when there are no more "RemainingInterfaceTs". +template +struct NodeInterfacesSupportCheck +{}; + +/// Default specialization, needs to be specialized for each supported interface. +template +struct NodeInterfacesSupports +{ + // Specializations need to set this to std::true_type in addition to other interfaces. + using is_supported = std::false_type; +}; + +/// Terminating specialization of NodeInterfacesSupports. +template +struct NodeInterfacesSupports + : public StorageClassT +{ + /// Perfect forwarding constructor to get arguments down to StorageClassT. + template + explicit NodeInterfacesSupports(ArgsT && ... args) + : StorageClassT(std::forward(args) ...) + {} +}; + +// Helper functions to initialize the tuple in NodeInterfaces. + +template +void +init_element(TupleT & t, NodeT & n) +{ + std::get>(t) = + NodeInterfacesSupports::get_from_node_like(n); +} + +template +std::tuple...> +init_tuple(NodeT & n) +{ + using StorageClassT = NodeInterfacesStorage; + std::tuple...> t; + (init_element(t, n), ...); + return t; +} + +/// Macro for creating specializations with less boilerplate. +/** + * You can use this macro to add support for your interface class if: + * + * - The standard getter is get_node_{NodeInterfaceName}_interface(), and + * - the getter returns a non-const shared_ptr<{NodeInterfaceType}> + * + * Examples of using this can be seen in the standard node interface headers + * in rclcpp, e.g. rclcpp/node_interfaces/node_base_interface.hpp has: + * + * RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeBaseInterface, base) + * + * If your interface has a non-standard getter, or you want to instrument it or + * something like that, then you'll need to create your own specialization of + * the NodeInterfacesSupports struct without this macro. + */ +#define RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(NodeInterfaceType, NodeInterfaceName) \ + namespace rclcpp::node_interfaces::detail { \ + template \ + struct NodeInterfacesSupports< \ + StorageClassT, \ + NodeInterfaceType, \ + RemainingInterfaceTs ...> \ + : public NodeInterfacesSupports \ + { \ + using is_supported = std::true_type; \ + \ + template \ + static \ + std::shared_ptr \ + get_from_node_like(NodeT & node_like) \ + { \ + return node_like.get_node_ ## NodeInterfaceName ## _interface(); \ + } \ + \ + /* Perfect forwarding constructor to get arguments down to StorageClassT (eventually). */ \ + template \ + explicit NodeInterfacesSupports(ArgsT && ... args) \ + : NodeInterfacesSupports( \ + std::forward(args) ...) \ + {} \ + \ + std::shared_ptr \ + get_node_ ## NodeInterfaceName ## _interface() \ + { \ + return StorageClassT::template get(); \ + } \ + }; \ + } // namespace rclcpp::node_interfaces::detail + +} // namespace detail +} // namespace node_interfaces +} // namespace rclcpp + +#endif // RCLCPP__NODE_INTERFACES__DETAIL__NODE_INTERFACES_HELPERS_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp index 90011a26e0..a6c84e4aa0 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp @@ -15,7 +15,7 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_BASE_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_BASE_HPP_ -#include +#include #include #include #include diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp index b0f8fbd65e..fd4f64b22b 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp @@ -15,10 +15,10 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_BASE_INTERFACE_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_BASE_INTERFACE_HPP_ +#include +#include #include -#include #include -#include #include "rcl/node.h" @@ -26,6 +26,7 @@ #include "rclcpp/context.hpp" #include "rclcpp/guard_condition.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/visibility_control.hpp" namespace rclcpp @@ -177,4 +178,6 @@ class NodeBaseInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeBaseInterface, base) + #endif // RCLCPP__NODE_INTERFACES__NODE_BASE_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_clock.hpp b/rclcpp/include/rclcpp/node_interfaces/node_clock.hpp index fd9a34a907..fb2e0670a7 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_clock.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_clock.hpp @@ -15,6 +15,7 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_CLOCK_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_CLOCK_HPP_ +#include "rcl/time.h" #include "rclcpp/clock.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" @@ -42,7 +43,8 @@ class NodeClock : public NodeClockInterface rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services, - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging); + rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, + rcl_clock_type_t clock_type); RCLCPP_PUBLIC virtual @@ -67,7 +69,7 @@ class NodeClock : public NodeClockInterface rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_; rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_; - rclcpp::Clock::SharedPtr ros_clock_; + rclcpp::Clock::SharedPtr clock_; }; } // namespace node_interfaces diff --git a/rclcpp/include/rclcpp/node_interfaces/node_clock_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_clock_interface.hpp index 8965a371d8..744eef4ce6 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_clock_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_clock_interface.hpp @@ -17,6 +17,7 @@ #include "rclcpp/clock.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/visibility_control.hpp" namespace rclcpp @@ -50,4 +51,6 @@ class NodeClockInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeClockInterface, clock) + #endif // RCLCPP__NODE_INTERFACES__NODE_CLOCK_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp b/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp index 794038d386..d167515784 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_graph.hpp @@ -15,7 +15,9 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_GRAPH_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_GRAPH_HPP_ +#include #include +#include #include #include #include diff --git a/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp index 3958f5b2d9..fefda0da69 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp @@ -29,6 +29,7 @@ #include "rclcpp/event.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/qos.hpp" #include "rclcpp/visibility_control.hpp" @@ -382,4 +383,6 @@ class NodeGraphInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeGraphInterface, graph) + #endif // RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_interfaces.hpp b/rclcpp/include/rclcpp/node_interfaces/node_interfaces.hpp new file mode 100644 index 0000000000..97959145b3 --- /dev/null +++ b/rclcpp/include/rclcpp/node_interfaces/node_interfaces.hpp @@ -0,0 +1,159 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP__NODE_INTERFACES__NODE_INTERFACES_HPP_ +#define RCLCPP__NODE_INTERFACES__NODE_INTERFACES_HPP_ + +#include + +#include "rclcpp/detail/template_unique.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" + +#define ALL_RCLCPP_NODE_INTERFACES \ + rclcpp::node_interfaces::NodeBaseInterface, \ + rclcpp::node_interfaces::NodeClockInterface, \ + rclcpp::node_interfaces::NodeGraphInterface, \ + rclcpp::node_interfaces::NodeLoggingInterface, \ + rclcpp::node_interfaces::NodeParametersInterface, \ + rclcpp::node_interfaces::NodeServicesInterface, \ + rclcpp::node_interfaces::NodeTimeSourceInterface, \ + rclcpp::node_interfaces::NodeTimersInterface, \ + rclcpp::node_interfaces::NodeTopicsInterface, \ + rclcpp::node_interfaces::NodeWaitablesInterface + + +namespace rclcpp +{ +namespace node_interfaces +{ + + +/// A helper class for aggregating node interfaces. +template +class NodeInterfaces + : public detail::NodeInterfacesSupportCheck< + detail::NodeInterfacesStorage, + InterfaceTs ... + >, + public detail::NodeInterfacesSupports< + detail::NodeInterfacesStorage, + InterfaceTs ... + > +{ + static_assert( + 0 != sizeof ...(InterfaceTs), + "must provide at least one interface as a template argument"); + static_assert( + rclcpp::detail::template_unique_v, + "must provide unique template parameters"); + + using NodeInterfacesSupportsT = detail::NodeInterfacesSupports< + detail::NodeInterfacesStorage, + InterfaceTs ... + >; + +public: + /// Create a new NodeInterfaces object using the given node-like object's interfaces. + /** + * Specify which interfaces you need by passing them as template parameters. + * + * This allows you to aggregate interfaces from different sources together to pass as a single + * aggregate object to any functions that take node interfaces or node-likes, without needing to + * templatize that function. + * + * You may also use this constructor to create a NodeInterfaces that contains a subset of + * another NodeInterfaces' interfaces. + * + * Finally, this class supports implicit conversion from node-like objects, allowing you to + * directly pass a node-like to a function that takes a NodeInterfaces object. + * + * Usage examples: + * ```cpp + * // Suppose we have some function: + * void fn(NodeInterfaces interfaces); + * + * // Then we can, explicitly: + * rclcpp::Node node("some_node"); + * auto ni = NodeInterfaces(node); + * fn(ni); + * + * // But also: + * fn(node); + * + * // Subsetting a NodeInterfaces object also works! + * auto ni_base = NodeInterfaces(ni); + * + * // Or aggregate them (you could aggregate interfaces from disparate node-likes) + * auto ni_aggregated = NodeInterfaces( + * node->get_node_base_interface(), + * node->get_node_clock_interface() + * ) + * + * // And then to access the interfaces: + * // Get with get<> + * auto base = ni.get(); + * + * // Or the appropriate getter + * auto clock = ni.get_clock_interface(); + * ``` + * + * You may use any of the standard node interfaces that come with rclcpp: + * - rclcpp::node_interfaces::NodeBaseInterface + * - rclcpp::node_interfaces::NodeClockInterface + * - rclcpp::node_interfaces::NodeGraphInterface + * - rclcpp::node_interfaces::NodeLoggingInterface + * - rclcpp::node_interfaces::NodeParametersInterface + * - rclcpp::node_interfaces::NodeServicesInterface + * - rclcpp::node_interfaces::NodeTimeSourceInterface + * - rclcpp::node_interfaces::NodeTimersInterface + * - rclcpp::node_interfaces::NodeTopicsInterface + * - rclcpp::node_interfaces::NodeWaitablesInterface + * + * Or you use custom interfaces as long as you make a template specialization + * of the rclcpp::node_interfaces::detail::NodeInterfacesSupport struct using + * the RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT macro. + * + * Usage example: + * ```RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeBaseInterface, base)``` + * + * If you choose not to use the helper macro, then you can specialize the + * template yourself, but you must: + * + * - Provide a template specialization of the get_from_node_like method that gets the interface + * from any node-like that stores the interface, using the node-like's getter + * - Designate the is_supported type as std::true_type using a using directive + * - Provide any number of getter methods to be used to obtain the interface with the + * NodeInterface object, noting that the getters of the storage class will apply to all + * supported interfaces. + * - The getter method names should not clash in name with any other interface getter + * specializations if those other interfaces are meant to be aggregated in the same + * NodeInterfaces object. + * + * \param[in] node Node-like object from which to get the node interfaces + */ + template + NodeInterfaces(NodeT & node) // NOLINT(runtime/explicit) + : NodeInterfacesSupportsT(node) + {} + + explicit NodeInterfaces(std::shared_ptr... args) + : NodeInterfacesSupportsT(args ...) + {} +}; + + +} // namespace node_interfaces +} // namespace rclcpp + +#endif // RCLCPP__NODE_INTERFACES__NODE_INTERFACES_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_logging_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_logging_interface.hpp index c2add566b9..870a81a53b 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_logging_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_logging_interface.hpp @@ -19,6 +19,7 @@ #include "rclcpp/logger.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/visibility_control.hpp" namespace rclcpp @@ -58,4 +59,6 @@ class NodeLoggingInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeLoggingInterface, logging) + #endif // RCLCPP__NODE_INTERFACES__NODE_LOGGING_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp index 7cc130f256..ffbb400c11 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp @@ -15,9 +15,10 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_HPP_ +#include #include #include -#include +#include #include #include @@ -181,20 +182,43 @@ class NodeParameters : public NodeParametersInterface rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const override; + RCLCPP_PUBLIC + RCUTILS_WARN_UNUSED + PreSetParametersCallbackHandle::SharedPtr + add_pre_set_parameters_callback(PreSetParametersCallbackType callback) override; + RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr - add_on_set_parameters_callback(OnParametersSetCallbackType callback) override; + add_on_set_parameters_callback(OnSetParametersCallbackType callback) override; + + RCLCPP_PUBLIC + RCUTILS_WARN_UNUSED + PostSetParametersCallbackHandle::SharedPtr + add_post_set_parameters_callback(PostSetParametersCallbackType callback) override; RCLCPP_PUBLIC void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler) override; + RCLCPP_PUBLIC + void + remove_post_set_parameters_callback(const PostSetParametersCallbackHandle * const handler) + override; + + RCLCPP_PUBLIC + void + remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle * const handler) override; + RCLCPP_PUBLIC const std::map & get_parameter_overrides() const override; - using CallbacksContainerType = std::list; + using PreSetCallbacksHandleContainer = std::list; + using OnSetCallbacksHandleContainer = std::list; + using PostSetCallbacksHandleContainer = std::list; + using CallbacksContainerType [[deprecated("use OnSetCallbacksHandleContainer instead")]] = + OnSetCallbacksHandleContainer; protected: RCLCPP_PUBLIC @@ -211,7 +235,11 @@ class NodeParameters : public NodeParametersInterface // declare_parameter, etc). In those cases, this will be set to false. bool parameter_modification_enabled_{true}; - CallbacksContainerType on_parameters_set_callback_container_; + PreSetCallbacksHandleContainer pre_set_parameters_callback_container_; + + OnSetCallbacksHandleContainer on_set_parameters_callback_container_; + + PostSetCallbacksHandleContainer post_set_parameters_callback_container_; std::map parameters_; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp index 743c1b8d4f..301c1e3214 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp @@ -15,8 +15,8 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ +#include #include -#include #include #include @@ -25,6 +25,7 @@ #include "rcl_interfaces/msg/set_parameters_result.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/parameter.hpp" #include "rclcpp/visibility_control.hpp" @@ -33,16 +34,38 @@ namespace rclcpp namespace node_interfaces { +struct PreSetParametersCallbackHandle +{ + RCLCPP_SMART_PTR_DEFINITIONS(PreSetParametersCallbackHandle) + + using PreSetParametersCallbackType = + std::function &)>; + + PreSetParametersCallbackType callback; +}; + struct OnSetParametersCallbackHandle { RCLCPP_SMART_PTR_DEFINITIONS(OnSetParametersCallbackHandle) - using OnParametersSetCallbackType = + using OnSetParametersCallbackType = std::function< rcl_interfaces::msg::SetParametersResult( const std::vector &)>; + using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] = + OnSetParametersCallbackType; - OnParametersSetCallbackType callback; + OnSetParametersCallbackType callback; +}; + +struct PostSetParametersCallbackHandle +{ + RCLCPP_SMART_PTR_DEFINITIONS(PostSetParametersCallbackHandle) + + using PostSetParametersCallbackType = + std::function &)>; + + PostSetParametersCallbackType callback; }; /// Pure virtual interface class for the NodeParameters part of the Node API. @@ -185,16 +208,46 @@ class NodeParametersInterface rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const = 0; - using OnParametersSetCallbackType = OnSetParametersCallbackHandle::OnParametersSetCallbackType; + using OnSetParametersCallbackType = OnSetParametersCallbackHandle::OnSetParametersCallbackType; + using PostSetParametersCallbackType = + PostSetParametersCallbackHandle::PostSetParametersCallbackType; + using PreSetParametersCallbackType = PreSetParametersCallbackHandle::PreSetParametersCallbackType; + + /// Add a callback that gets triggered before parameters are validated. + /** + * \sa rclcpp::Node::add_pre_set_parameters_callback + */ + RCLCPP_PUBLIC + virtual + PreSetParametersCallbackHandle::SharedPtr + add_pre_set_parameters_callback(PreSetParametersCallbackType callback) = 0; - /// Add a callback for when parameters are being set. + /// Add a callback to validate parameters before they are set. /** * \sa rclcpp::Node::add_on_set_parameters_callback */ RCLCPP_PUBLIC virtual OnSetParametersCallbackHandle::SharedPtr - add_on_set_parameters_callback(OnParametersSetCallbackType callback) = 0; + add_on_set_parameters_callback(OnSetParametersCallbackType callback) = 0; + + /// Add a callback that gets triggered after parameters are set successfully. + /** + * \sa rclcpp::Node::add_post_set_parameters_callback + */ + RCLCPP_PUBLIC + virtual + PostSetParametersCallbackHandle::SharedPtr + add_post_set_parameters_callback(PostSetParametersCallbackType callback) = 0; + + /// Remove a callback registered with `add_pre_set_parameters_callback`. + /** + * \sa rclcpp::Node::remove_pre_set_parameters_callback + */ + RCLCPP_PUBLIC + virtual + void + remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle * const handler) = 0; /// Remove a callback registered with `add_on_set_parameters_callback`. /** @@ -205,6 +258,15 @@ class NodeParametersInterface void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler) = 0; + /// Remove a callback registered with `add_post_set_parameters_callback`. + /** + * \sa rclcpp::Node::remove_post_set_parameters_callback + */ + RCLCPP_PUBLIC + virtual + void + remove_post_set_parameters_callback(const PostSetParametersCallbackHandle * const handler) = 0; + /// Return the initial parameter values used by the NodeParameters to override default values. RCLCPP_PUBLIC virtual @@ -215,4 +277,6 @@ class NodeParametersInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeParametersInterface, parameters) + #endif // RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp index ab6cdab42e..ff58ef36b6 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp @@ -20,6 +20,7 @@ #include "rclcpp/callback_group.hpp" #include "rclcpp/client.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/service.hpp" #include "rclcpp/visibility_control.hpp" @@ -62,4 +63,6 @@ class NodeServicesInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeServicesInterface, services) + #endif // RCLCPP__NODE_INTERFACES__NODE_SERVICES_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_time_source_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_time_source_interface.hpp index 5b7065193e..3783e5d83a 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_time_source_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_time_source_interface.hpp @@ -16,6 +16,7 @@ #define RCLCPP__NODE_INTERFACES__NODE_TIME_SOURCE_INTERFACE_HPP_ #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/visibility_control.hpp" namespace rclcpp @@ -37,4 +38,6 @@ class NodeTimeSourceInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeTimeSourceInterface, time_source) + #endif // RCLCPP__NODE_INTERFACES__NODE_TIME_SOURCE_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp index 4573d3d02b..2f1aaef51e 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp @@ -17,6 +17,7 @@ #include "rclcpp/callback_group.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/timer.hpp" #include "rclcpp/visibility_control.hpp" @@ -47,4 +48,6 @@ class NodeTimersInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeTimersInterface, timers) + #endif // RCLCPP__NODE_INTERFACES__NODE_TIMERS_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp index ca69e86e73..aa5530f8dd 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp @@ -15,8 +15,6 @@ #ifndef RCLCPP__NODE_INTERFACES__NODE_TOPICS_INTERFACE_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_TOPICS_INTERFACE_HPP_ -#include -#include #include #include "rcl/publisher.h" @@ -24,6 +22,7 @@ #include "rclcpp/callback_group.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" #include "rclcpp/node_interfaces/node_timers_interface.hpp" #include "rclcpp/publisher.hpp" @@ -97,4 +96,6 @@ class NodeTopicsInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeTopicsInterface, topics) + #endif // RCLCPP__NODE_INTERFACES__NODE_TOPICS_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp index 0faae1da62..fd0029a89b 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp @@ -17,6 +17,7 @@ #include "rclcpp/callback_group.hpp" #include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" #include "rclcpp/visibility_control.hpp" #include "rclcpp/waitable.hpp" @@ -54,4 +55,6 @@ class NodeWaitablesInterface } // namespace node_interfaces } // namespace rclcpp +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeWaitablesInterface, waitables) + #endif // RCLCPP__NODE_INTERFACES__NODE_WAITABLES_INTERFACE_HPP_ diff --git a/rclcpp/include/rclcpp/node_options.hpp b/rclcpp/include/rclcpp/node_options.hpp index d9735357dd..47a97fd3c4 100644 --- a/rclcpp/include/rclcpp/node_options.hpp +++ b/rclcpp/include/rclcpp/node_options.hpp @@ -19,6 +19,7 @@ #include #include +#include "rcl/time.h" #include "rcl/node_options.h" #include "rclcpp/context.hpp" #include "rclcpp/contexts/default_context.hpp" @@ -46,6 +47,7 @@ class NodeOptions * - enable_topic_statistics = false * - start_parameter_services = true * - start_parameter_event_publisher = true + * - clock_type = RCL_ROS_TIME * - clock_qos = rclcpp::ClockQoS() * - use_clock_thread = true * - rosout_qos = rclcpp::RosoutQoS() @@ -246,6 +248,19 @@ class NodeOptions NodeOptions & start_parameter_event_publisher(bool start_parameter_event_publisher); + /// Return a reference to the clock type. + RCLCPP_PUBLIC + const rcl_clock_type_t & + clock_type() const; + + /// Set the clock type. + /** + * The clock type to be used by the node. + */ + RCLCPP_PUBLIC + NodeOptions & + clock_type(const rcl_clock_type_t & clock_type); + /// Return a reference to the clock QoS. RCLCPP_PUBLIC const rclcpp::QoS & @@ -400,6 +415,8 @@ class NodeOptions bool start_parameter_event_publisher_ {true}; + rcl_clock_type_t clock_type_ {RCL_ROS_TIME}; + rclcpp::QoS clock_qos_ = rclcpp::ClockQoS(); bool use_clock_thread_ {true}; diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 5e509bbf10..7dff6e9ad6 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -39,6 +39,7 @@ #include "rclcpp/node.hpp" #include "rclcpp/parameter.hpp" #include "rclcpp/parameter_map.hpp" +#include "rclcpp/qos.hpp" #include "rclcpp/type_support_decl.hpp" #include "rclcpp/visibility_control.hpp" #include "rmw/rmw.h" @@ -51,6 +52,37 @@ class AsyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient) + /// Create an async parameters client. + /** + * \param[in] node_base_interface The node base interface of the corresponding node. + * \param[in] node_topics_interface Node topic base interface. + * \param[in] node_graph_interface The node graph interface of the corresponding node. + * \param[in] node_services_interface Node service interface. + * \param[in] remote_node_name Name of the remote node + * \param[in] qos_profile The rmw qos profile to use to subscribe + * \param[in] group (optional) The async parameter client will be added to this callback group. + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + RCLCPP_PUBLIC + AsyncParametersClient( + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, + const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, + const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, + const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile, + rclcpp::CallbackGroup::SharedPtr group = nullptr) + : AsyncParametersClient( + node_base_interface, + node_topics_interface, + node_graph_interface, + node_services_interface, + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)), + group) + {} + /// Create an async parameters client. /** * \param[in] node_base_interface The node base interface of the corresponding node. @@ -58,7 +90,7 @@ class AsyncParametersClient * \param[in] node_graph_interface The node graph interface of the corresponding node. * \param[in] node_services_interface Node service interface. * \param[in] remote_node_name (optional) name of the remote node - * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe + * \param[in] qos_profile (optional) The qos profile to use to subscribe * \param[in] group (optional) The async parameter client will be added to this callback group. */ RCLCPP_PUBLIC @@ -68,21 +100,45 @@ class AsyncParametersClient const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Constructor /** - * \param[in] node The async paramters client will be added to this node. + * \param[in] node The async parameters client will be added to this node. + * \param[in] remote_node_name name of the remote node + * \param[in] qos_profile The rmw qos profile to use to subscribe + * \param[in] group (optional) The async parameter client will be added to this callback group. + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + AsyncParametersClient( + const std::shared_ptr node, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile, + rclcpp::CallbackGroup::SharedPtr group = nullptr) + : AsyncParametersClient( + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)), + group) + {} + + /** + * \param[in] node The async parameters client will be added to this node. * \param[in] remote_node_name (optional) name of the remote node - * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe + * \param[in] qos_profile (optional) The qos profile to use to subscribe * \param[in] group (optional) The async parameter client will be added to this callback group. */ template explicit AsyncParametersClient( const std::shared_ptr node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr) : AsyncParametersClient( node->get_node_base_interface(), @@ -96,16 +152,40 @@ class AsyncParametersClient /// Constructor /** - * \param[in] node The async paramters client will be added to this node. + * \param[in] node The async parameters client will be added to this node. + * \param[in] remote_node_name Name of the remote node + * \param[in] qos_profile The rmw qos profile to use to subscribe + * \param[in] group (optional) The async parameter client will be added to this callback group. + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + AsyncParametersClient( + NodeT * node, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile, + rclcpp::CallbackGroup::SharedPtr group = nullptr) + : AsyncParametersClient( + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)), + group) + {} + + /** + * \param[in] node The async parameters client will be added to this node. * \param[in] remote_node_name (optional) name of the remote node - * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe + * \param[in] qos_profile (optional) The qos profile to use to subscribe * \param[in] group (optional) The async parameter client will be added to this callback group. */ template explicit AsyncParametersClient( NodeT * node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr) : AsyncParametersClient( node->get_node_base_interface(), @@ -185,6 +265,9 @@ class AsyncParametersClient /** * This function filters the parameters to be set based on the node name. * + * If two duplicate keys exist in node names belongs to one FQN, there is no guarantee + * which one could be set. + * * \param parameter_map named parameters to be loaded * \return the future of the set_parameter service used to load the parameters * \throw InvalidParametersException if there is no parameter to set @@ -208,9 +291,7 @@ class AsyncParametersClient typename rclcpp::Subscription::SharedPtr on_parameter_event( CallbackT && callback, - const rclcpp::QoS & qos = ( - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)) - ), + const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(), const rclcpp::SubscriptionOptionsWithAllocator & options = ( rclcpp::SubscriptionOptionsWithAllocator() )) @@ -235,9 +316,7 @@ class AsyncParametersClient on_parameter_event( NodeT && node, CallbackT && callback, - const rclcpp::QoS & qos = ( - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)) - ), + const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(), const rclcpp::SubscriptionOptionsWithAllocator & options = ( rclcpp::SubscriptionOptionsWithAllocator() )) @@ -304,11 +383,24 @@ class SyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient) + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + SyncParametersClient( + std::shared_ptr node, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile) + : SyncParametersClient( + std::make_shared(), + node, + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) + {} + template explicit SyncParametersClient( std::shared_ptr node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()) : SyncParametersClient( std::make_shared(), node, @@ -316,12 +408,29 @@ class SyncParametersClient qos_profile) {} + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + SyncParametersClient( + rclcpp::Executor::SharedPtr executor, + std::shared_ptr node, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile) + : SyncParametersClient( + executor, + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) + {} + template SyncParametersClient( rclcpp::Executor::SharedPtr executor, std::shared_ptr node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()) : SyncParametersClient( executor, node->get_node_base_interface(), @@ -332,11 +441,24 @@ class SyncParametersClient qos_profile) {} + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + SyncParametersClient( + NodeT * node, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile) + : SyncParametersClient( + std::make_shared(), + node, + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) + {} + template explicit SyncParametersClient( NodeT * node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()) : SyncParametersClient( std::make_shared(), node, @@ -344,12 +466,29 @@ class SyncParametersClient qos_profile) {} + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + SyncParametersClient( + rclcpp::Executor::SharedPtr executor, + NodeT * node, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile) + : SyncParametersClient( + executor, + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) + {} + template SyncParametersClient( rclcpp::Executor::SharedPtr executor, NodeT * node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()) : SyncParametersClient( executor, node->get_node_base_interface(), @@ -360,6 +499,28 @@ class SyncParametersClient qos_profile) {} + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + RCLCPP_PUBLIC + SyncParametersClient( + rclcpp::Executor::SharedPtr executor, + const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, + const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, + const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, + const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, + const std::string & remote_node_name, + const rmw_qos_profile_t & qos_profile) + : executor_(executor), node_base_interface_(node_base_interface) + { + async_parameters_client_ = + std::make_shared( + node_base_interface, + node_topics_interface, + node_graph_interface, + node_services_interface, + remote_node_name, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))); + } + RCLCPP_PUBLIC SyncParametersClient( rclcpp::Executor::SharedPtr executor, @@ -368,7 +529,7 @@ class SyncParametersClient const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()) : executor_(executor), node_base_interface_(node_base_interface) { async_parameters_client_ = diff --git a/rclcpp/include/rclcpp/parameter_event_handler.hpp b/rclcpp/include/rclcpp/parameter_event_handler.hpp index 52a0233966..93b8177fb2 100644 --- a/rclcpp/include/rclcpp/parameter_event_handler.hpp +++ b/rclcpp/include/rclcpp/parameter_event_handler.hpp @@ -86,6 +86,9 @@ struct ParameterEventCallbackHandle * the ROS node supplied in the ParameterEventHandler constructor. * The callback, a lambda function in this case, simply prints out the value of the parameter. * + * Note: the object returned from add_parameter_callback must be captured or the callback will + * be immediately unregistered. + * * You may also monitor for changes to parameters in other nodes by supplying the node * name to add_parameter_callback: * @@ -103,8 +106,8 @@ struct ParameterEventCallbackHandle * In this case, the callback will be invoked whenever "some_remote_param_name" changes * on remote node "some_remote_node_name". * - * To remove a parameter callback, call remove_parameter_callback, passing the handle returned - * from add_parameter_callback: + * To remove a parameter callback, reset the callback handle smart pointer or call + * remove_parameter_callback, passing the handle returned from add_parameter_callback: * * param_handler->remove_parameter_callback(handle2); * @@ -152,9 +155,12 @@ struct ParameterEventCallbackHandle * For both parameter callbacks and parameter event callbacks, when multiple callbacks are added, * the callbacks are invoked last-in, first-called order (LIFO). * - * To remove a parameter event callback, use: + * Note: the callback handle returned from add_parameter_event_callback must be captured or + * the callback will immediately be unregistered. + * + * To remove a parameter event callback, reset the callback smart pointer or use: * - * param_handler->remove_event_parameter_callback(handle); + * param_handler->remove_event_parameter_callback(handle3); */ class ParameterEventHandler { @@ -189,10 +195,14 @@ class ParameterEventHandler /** * This function may be called multiple times to set multiple parameter event callbacks. * + * Note: if the returned callback handle smart pointer is not captured, the callback is + * immediatedly unregistered. A compiler warning should be generated to warn of this. + * * \param[in] callback Function callback to be invoked on parameter updates. * \returns A handle used to refer to the callback. */ RCLCPP_PUBLIC + RCUTILS_WARN_UNUSED ParameterEventCallbackHandle::SharedPtr add_parameter_event_callback( ParameterEventCallbackType callback); @@ -212,12 +222,17 @@ class ParameterEventHandler /** * If a node_name is not provided, defaults to the current node. * + * Note: if the returned callback handle smart pointer is not captured, the callback + * is immediately unregistered. A compiler warning should be generated to warn + * of this. + * * \param[in] parameter_name Name of parameter to monitor. * \param[in] callback Function callback to be invoked upon parameter update. * \param[in] node_name Name of node which hosts the parameter. * \returns A handle used to refer to the callback. */ RCLCPP_PUBLIC + RCUTILS_WARN_UNUSED ParameterCallbackHandle::SharedPtr add_parameter_callback( const std::string & parameter_name, diff --git a/rclcpp/include/rclcpp/parameter_map.hpp b/rclcpp/include/rclcpp/parameter_map.hpp index 9cfcdaaacf..17e2128a7b 100644 --- a/rclcpp/include/rclcpp/parameter_map.hpp +++ b/rclcpp/include/rclcpp/parameter_map.hpp @@ -35,11 +35,13 @@ using ParameterMap = std::unordered_map>; /// Convert parameters from rcl_yaml_param_parser into C++ class instances. /// \param[in] c_params C structures containing parameters for multiple nodes. +/// \param[in] node_fqn a Fully Qualified Name of node, default value is nullptr. +/// If it's not nullptr, return the relative node parameters belonging to this node_fqn. /// \returns a map where the keys are fully qualified node names and values a list of parameters. /// \throws InvalidParametersException if the `rcl_params_t` is inconsistent or invalid. RCLCPP_PUBLIC ParameterMap -parameter_map_from(const rcl_params_t * const c_params); +parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn = nullptr); /// Convert parameter value from rcl_yaml_param_parser into a C++ class instance. /// \param[in] c_value C structure containing a value of a parameter. @@ -51,11 +53,20 @@ parameter_value_from(const rcl_variant_t * const c_value); /// Get the ParameterMap from a yaml file. /// \param[in] yaml_filename full name of the yaml file. +/// \param[in] node_fqn a Fully Qualified Name of node, default value is nullptr. /// \returns an instance of a parameter map /// \throws from rcl error of rcl_parse_yaml_file() RCLCPP_PUBLIC ParameterMap -parameter_map_from_yaml_file(const std::string & yaml_filename); +parameter_map_from_yaml_file(const std::string & yaml_filename, const char * node_fqn = nullptr); + +/// Get the Parameters from ParameterMap. +/// \param[in] parameter_map a parameter map. +/// \param[in] node_fqn a Fully Qualified Name of node, default value is nullptr. +/// \returns a list of a parameter +RCLCPP_PUBLIC +std::vector +parameters_from_map(const ParameterMap & parameter_map, const char * node_fqn = nullptr); } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/parameter_service.hpp b/rclcpp/include/rclcpp/parameter_service.hpp index 143a5223c8..a952939aca 100644 --- a/rclcpp/include/rclcpp/parameter_service.hpp +++ b/rclcpp/include/rclcpp/parameter_service.hpp @@ -28,6 +28,7 @@ #include "rclcpp/macros.hpp" #include "rclcpp/node.hpp" #include "rclcpp/parameter.hpp" +#include "rclcpp/qos.hpp" #include "rclcpp/visibility_control.hpp" #include "rmw/rmw.h" @@ -39,12 +40,26 @@ class ParameterService public: RCLCPP_SMART_PTR_DEFINITIONS(ParameterService) + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] RCLCPP_PUBLIC - explicit ParameterService( + ParameterService( const std::shared_ptr node_base, const std::shared_ptr node_services, rclcpp::node_interfaces::NodeParametersInterface * node_params, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + const rmw_qos_profile_t & qos_profile) + : ParameterService( + node_base, + node_services, + node_params, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) + {} + + RCLCPP_PUBLIC + ParameterService( + const std::shared_ptr node_base, + const std::shared_ptr node_services, + rclcpp::node_interfaces::NodeParametersInterface * node_params, + const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()); private: rclcpp::Service::SharedPtr get_parameters_service_; diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 78b5700611..43fa4ef6a2 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -131,40 +131,16 @@ class Publisher : public PublisherBase node_base, topic, rclcpp::get_message_type_support_handle(), - options.template to_rcl_publisher_options(qos)), + options.template to_rcl_publisher_options(qos), + // NOTE(methylDragon): Passing these args separately is necessary for event binding + options.event_callbacks, + options.use_default_callbacks), options_(options), published_type_allocator_(*options.get_allocator()), ros_message_type_allocator_(*options.get_allocator()) { allocator::set_allocator_for_deleter(&published_type_deleter_, &published_type_allocator_); allocator::set_allocator_for_deleter(&ros_message_type_deleter_, &ros_message_type_allocator_); - - if (options_.event_callbacks.deadline_callback) { - this->add_event_handler( - options_.event_callbacks.deadline_callback, - RCL_PUBLISHER_OFFERED_DEADLINE_MISSED); - } - if (options_.event_callbacks.liveliness_callback) { - this->add_event_handler( - options_.event_callbacks.liveliness_callback, - RCL_PUBLISHER_LIVELINESS_LOST); - } - if (options_.event_callbacks.incompatible_qos_callback) { - this->add_event_handler( - options_.event_callbacks.incompatible_qos_callback, - RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS); - } else if (options_.use_default_callbacks) { - // Register default callback when not specified - try { - this->add_event_handler( - [this](QOSOfferedIncompatibleQoSInfo & info) { - this->default_incompatible_qos_callback(info); - }, - RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS); - } catch (UnsupportedEventTypeException & /*exc*/) { - // pass - } - } // Setup continues in the post construction method, post_init_setup(). } diff --git a/rclcpp/include/rclcpp/publisher_base.hpp b/rclcpp/include/rclcpp/publisher_base.hpp index 8416757a53..153d5a6ebe 100644 --- a/rclcpp/include/rclcpp/publisher_base.hpp +++ b/rclcpp/include/rclcpp/publisher_base.hpp @@ -78,11 +78,18 @@ class PublisherBase : public std::enable_shared_from_this rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic, const rosidl_message_type_support_t & type_support, - const rcl_publisher_options_t & publisher_options); + const rcl_publisher_options_t & publisher_options, + const PublisherEventCallbacks & event_callbacks, + bool use_default_callbacks); RCLCPP_PUBLIC virtual ~PublisherBase(); + /// Add event handlers for passed in event_callbacks. + RCLCPP_PUBLIC + void + bind_event_callbacks(const PublisherEventCallbacks & event_callbacks, bool use_default_callbacks); + /// Get the topic that this publisher publishes on. /** \return The topic name. */ RCLCPP_PUBLIC @@ -348,6 +355,8 @@ class PublisherBase : public std::enable_shared_from_this rmw_gid_t rmw_gid_; const rosidl_message_type_support_t type_support_; + + const PublisherEventCallbacks event_callbacks_; }; } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/qos.hpp b/rclcpp/include/rclcpp/qos.hpp index 4946d37889..2ad49487c5 100644 --- a/rclcpp/include/rclcpp/qos.hpp +++ b/rclcpp/include/rclcpp/qos.hpp @@ -80,7 +80,9 @@ struct RCLCPP_PUBLIC QoSInitialization size_t depth; /// Constructor which takes both a history policy and a depth (even if it would be unused). - QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg); + QoSInitialization( + rmw_qos_history_policy_t history_policy_arg, size_t depth_arg, + bool print_depth_warning = true); /// Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth. static @@ -97,7 +99,7 @@ struct RCLCPP_PUBLIC KeepAll : public rclcpp::QoSInitialization /// Use to initialize the QoS with the keep_last history setting and the given depth. struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization { - explicit KeepLast(size_t depth); + explicit KeepLast(size_t depth, bool print_depth_warning = true); }; /// Encapsulation of Quality of Service settings. diff --git a/rclcpp/include/rclcpp/qos_event.hpp b/rclcpp/include/rclcpp/qos_event.hpp index f258c5d5ba..b48854c4bd 100644 --- a/rclcpp/include/rclcpp/qos_event.hpp +++ b/rclcpp/include/rclcpp/qos_event.hpp @@ -185,7 +185,7 @@ class QOSEventHandlerBase : public Waitable // This two-step setting, prevents a gap where the old std::function has // been replaced but the middleware hasn't been told about the new one yet. set_on_new_event_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline, static_cast(&new_callback)); // Store the std::function to keep it in scope, also overwrites the existing one. @@ -193,7 +193,8 @@ class QOSEventHandlerBase : public Waitable // Set it again, now using the permanent storage. set_on_new_event_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline< + decltype(on_new_event_callback_), const void *, size_t>, static_cast(&on_new_event_callback_)); } diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 3f500eaa09..9e258a0223 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -55,7 +55,7 @@ class ServiceBase explicit ServiceBase(std::shared_ptr node_handle); RCLCPP_PUBLIC - virtual ~ServiceBase(); + virtual ~ServiceBase() = default; /// Return the name of the service. /** \return The name of the service. */ @@ -222,7 +222,7 @@ class ServiceBase // This two-step setting, prevents a gap where the old std::function has // been replaced but the middleware hasn't been told about the new one yet. set_on_new_request_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline, static_cast(&new_callback)); // Store the std::function to keep it in scope, also overwrites the existing one. @@ -230,7 +230,8 @@ class ServiceBase // Set it again, now using the permanent storage. set_on_new_request_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline< + decltype(on_new_request_callback_), const void *, size_t>, static_cast(&on_new_request_callback_)); } diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 11bf9c6e43..d9e84b29f8 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -140,44 +140,15 @@ class Subscription : public SubscriptionBase node_base, type_support_handle, topic_name, - options.template to_rcl_subscription_options(qos), + options.to_rcl_subscription_options(qos), + // NOTE(methylDragon): Passing these args separately is necessary for event binding + options.event_callbacks, + options.use_default_callbacks, callback.is_serialized_message_callback()), any_callback_(callback), options_(options), message_memory_strategy_(message_memory_strategy) { - if (options_.event_callbacks.deadline_callback) { - this->add_event_handler( - options_.event_callbacks.deadline_callback, - RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED); - } - if (options_.event_callbacks.liveliness_callback) { - this->add_event_handler( - options_.event_callbacks.liveliness_callback, - RCL_SUBSCRIPTION_LIVELINESS_CHANGED); - } - if (options_.event_callbacks.incompatible_qos_callback) { - this->add_event_handler( - options_.event_callbacks.incompatible_qos_callback, - RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS); - } else if (options_.use_default_callbacks) { - // Register default callback when not specified - try { - this->add_event_handler( - [this](QOSRequestedIncompatibleQoSInfo & info) { - this->default_incompatible_qos_callback(info); - }, - RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS); - } catch (UnsupportedEventTypeException & /*exc*/) { - // pass - } - } - if (options_.event_callbacks.message_lost_callback) { - this->add_event_handler( - options_.event_callbacks.message_lost_callback, - RCL_SUBSCRIPTION_MESSAGE_LOST); - } - // Setup intra process publishing if requested. if (rclcpp::detail::resolve_use_intra_process(options_, *node_base)) { using rclcpp::detail::resolve_intra_process_buffer_type; diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index f21f27e864..b1aeb4eb7d 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -84,12 +84,20 @@ class SubscriptionBase : public std::enable_shared_from_this const rosidl_message_type_support_t & type_support_handle, const std::string & topic_name, const rcl_subscription_options_t & subscription_options, + const SubscriptionEventCallbacks & event_callbacks, + bool use_default_callbacks, bool is_serialized = false); /// Destructor. RCLCPP_PUBLIC virtual ~SubscriptionBase(); + /// Add event handlers for passed in event_callbacks. + RCLCPP_PUBLIC + void + bind_event_callbacks( + const SubscriptionEventCallbacks & event_callbacks, bool use_default_callbacks); + /// Get the topic that this subscription is subscribed on. RCLCPP_PUBLIC const char * @@ -348,7 +356,7 @@ class SubscriptionBase : public std::enable_shared_from_this // This two-step setting, prevents a gap where the old std::function has // been replaced but the middleware hasn't been told about the new one yet. set_on_new_message_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline, static_cast(&new_callback)); // Store the std::function to keep it in scope, also overwrites the existing one. @@ -356,7 +364,8 @@ class SubscriptionBase : public std::enable_shared_from_this // Set it again, now using the permanent storage. set_on_new_message_callback( - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline< + decltype(on_new_message_callback_), const void *, size_t>, static_cast(&on_new_message_callback_)); } @@ -569,6 +578,8 @@ class SubscriptionBase : public std::enable_shared_from_this uint64_t intra_process_subscription_id_; std::shared_ptr subscription_intra_process_; + const SubscriptionEventCallbacks event_callbacks_; + private: RCLCPP_DISABLE_COPY(SubscriptionBase) diff --git a/rclcpp/include/rclcpp/subscription_options.hpp b/rclcpp/include/rclcpp/subscription_options.hpp index 2b819da399..c5c3e21eb1 100644 --- a/rclcpp/include/rclcpp/subscription_options.hpp +++ b/rclcpp/include/rclcpp/subscription_options.hpp @@ -110,7 +110,6 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase * \param qos QoS profile for subcription. * \return rcl_subscription_options_t structure based on the rclcpp::QoS */ - template rcl_subscription_options_t to_rcl_subscription_options(const rclcpp::QoS & qos) const { diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index 5274cba33a..5b4ea86a6d 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -169,7 +169,7 @@ remove_ros_arguments(int argc, char const * const * argv); * the context initialized by rclcpp::init(). * * \param[in] context Optional check for shutdown of this Context. - * \return true if shutdown has been called, false otherwise + * \return false if shutdown has been called, true otherwise */ RCLCPP_PUBLIC bool diff --git a/rclcpp/package.xml b/rclcpp/package.xml index 6de7d25d07..a18cd7ae1d 100644 --- a/rclcpp/package.xml +++ b/rclcpp/package.xml @@ -2,13 +2,17 @@ rclcpp - 16.2.0 + 18.0.0 The ROS client library in C++. + Ivan Paunovic - Jacob Perron + Michel Hidalgo William Woodall + Apache License 2.0 + Dirk Thomas + Jacob Perron ament_cmake_ros ament_cmake_gen_version_h diff --git a/rclcpp/resource/logging.hpp.em b/rclcpp/resource/logging.hpp.em index 63581ceb54..01087e5dd0 100644 --- a/rclcpp/resource/logging.hpp.em +++ b/rclcpp/resource/logging.hpp.em @@ -124,7 +124,7 @@ def get_rclcpp_suffix_from_features(features): ) \ do { \ static_assert( \ - ::std::is_same::type>::type, \ + ::std::is_same>, \ typename ::rclcpp::Logger>::value, \ "First argument to logging macros must be an rclcpp::Logger"); \ @[ if 'throttle' in feature_combination]@ \ diff --git a/rclcpp/src/rclcpp/callback_group.cpp b/rclcpp/src/rclcpp/callback_group.cpp index 4b11156cf9..734c781a69 100644 --- a/rclcpp/src/rclcpp/callback_group.cpp +++ b/rclcpp/src/rclcpp/callback_group.cpp @@ -12,9 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rclcpp/callback_group.hpp" +#include +#include +#include +#include +#include +#include -#include +#include "rclcpp/callback_group.hpp" +#include "rclcpp/client.hpp" +#include "rclcpp/service.hpp" +#include "rclcpp/subscription_base.hpp" +#include "rclcpp/timer.hpp" +#include "rclcpp/waitable.hpp" using rclcpp::CallbackGroup; using rclcpp::CallbackGroupType; @@ -27,6 +37,10 @@ CallbackGroup::CallbackGroup( automatically_add_to_executor_with_node_(automatically_add_to_executor_with_node) {} +CallbackGroup::~CallbackGroup() +{ + trigger_notify_guard_condition(); +} std::atomic_bool & CallbackGroup::can_be_taken_from() @@ -97,6 +111,33 @@ CallbackGroup::automatically_add_to_executor_with_node() const return automatically_add_to_executor_with_node_; } +rclcpp::GuardCondition::SharedPtr +CallbackGroup::get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr) +{ + std::lock_guard lock(notify_guard_condition_mutex_); + if (notify_guard_condition_ && context_ptr != notify_guard_condition_->get_context()) { + if (associated_with_executor_) { + trigger_notify_guard_condition(); + } + notify_guard_condition_ = nullptr; + } + + if (!notify_guard_condition_) { + notify_guard_condition_ = std::make_shared(context_ptr); + } + + return notify_guard_condition_; +} + +void +CallbackGroup::trigger_notify_guard_condition() +{ + std::lock_guard lock(notify_guard_condition_mutex_); + if (notify_guard_condition_) { + notify_guard_condition_->trigger(); + } +} + void CallbackGroup::add_subscription( const rclcpp::SubscriptionBase::SharedPtr subscription_ptr) diff --git a/rclcpp/src/rclcpp/client.cpp b/rclcpp/src/rclcpp/client.cpp index 17cc68e153..4adc6d4a96 100644 --- a/rclcpp/src/rclcpp/client.cpp +++ b/rclcpp/src/rclcpp/client.cpp @@ -65,13 +65,6 @@ ClientBase::ClientBase( }); } -ClientBase::~ClientBase() -{ - clear_on_new_response_callback(); - // Make sure the client handle is destructed as early as possible and before the node handle - client_handle_.reset(); -} - bool ClientBase::take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out) { diff --git a/rclcpp/src/rclcpp/clock.cpp b/rclcpp/src/rclcpp/clock.cpp index 66c8db70e1..f46649a77d 100644 --- a/rclcpp/src/rclcpp/clock.cpp +++ b/rclcpp/src/rclcpp/clock.cpp @@ -67,7 +67,7 @@ Clock::Clock(rcl_clock_type_t clock_type) Clock::~Clock() {} Time -Clock::now() +Clock::now() const { Time now(0, 0, impl_->rcl_clock_.type); @@ -182,6 +182,71 @@ Clock::sleep_for(Duration rel_time, Context::SharedPtr context) return sleep_until(now() + rel_time, context); } +bool +Clock::started() +{ + if (!rcl_clock_valid(get_clock_handle())) { + throw std::runtime_error("clock is not rcl_clock_valid"); + } + return rcl_clock_time_started(get_clock_handle()); +} + +bool +Clock::wait_until_started(Context::SharedPtr context) +{ + if (!context || !context->is_valid()) { + throw std::runtime_error("context cannot be slept with because it's invalid"); + } + if (!rcl_clock_valid(get_clock_handle())) { + throw std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid"); + } + + if (started()) { + return true; + } else { + // Wait until the first non-zero time + return sleep_until(rclcpp::Time(0, 1, get_clock_type()), context); + } +} + +bool +Clock::wait_until_started( + const Duration & timeout, + Context::SharedPtr context, + const Duration & wait_tick_ns) +{ + if (!context || !context->is_valid()) { + throw std::runtime_error("context cannot be slept with because it's invalid"); + } + if (!rcl_clock_valid(get_clock_handle())) { + throw std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid"); + } + + Clock timeout_clock = Clock(RCL_STEADY_TIME); + Time start = timeout_clock.now(); + + // Check if the clock has started every wait_tick_ns nanoseconds + // Context check checks for rclcpp::shutdown() + while (!started() && context->is_valid()) { + if (timeout < wait_tick_ns) { + timeout_clock.sleep_for(timeout); + } else { + Duration time_left = start + timeout - timeout_clock.now(); + if (time_left > wait_tick_ns) { + timeout_clock.sleep_for(Duration(wait_tick_ns)); + } else { + timeout_clock.sleep_for(time_left); + } + } + + if (timeout_clock.now() - start > timeout) { + return started(); + } + } + return started(); +} + + bool Clock::ros_time_is_active() { diff --git a/rclcpp/src/rclcpp/context.cpp b/rclcpp/src/rclcpp/context.cpp index 1599172e2e..971c0ee73a 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -365,49 +365,45 @@ Context::on_shutdown(OnShutdownCallback callback) rclcpp::OnShutdownCallbackHandle Context::add_on_shutdown_callback(OnShutdownCallback callback) { - return add_shutdown_callback(ShutdownType::on_shutdown, callback); + return add_shutdown_callback(callback); } bool Context::remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_handle) { - return remove_shutdown_callback(ShutdownType::on_shutdown, callback_handle); + return remove_shutdown_callback(callback_handle); } rclcpp::PreShutdownCallbackHandle Context::add_pre_shutdown_callback(PreShutdownCallback callback) { - return add_shutdown_callback(ShutdownType::pre_shutdown, callback); + return add_shutdown_callback(callback); } bool Context::remove_pre_shutdown_callback( const PreShutdownCallbackHandle & callback_handle) { - return remove_shutdown_callback(ShutdownType::pre_shutdown, callback_handle); + return remove_shutdown_callback(callback_handle); } +template rclcpp::ShutdownCallbackHandle Context::add_shutdown_callback( - ShutdownType shutdown_type, ShutdownCallback callback) { auto callback_shared_ptr = std::make_shared(callback); - switch (shutdown_type) { - case ShutdownType::pre_shutdown: - { - std::lock_guard lock(pre_shutdown_callbacks_mutex_); - pre_shutdown_callbacks_.emplace(callback_shared_ptr); - } - break; - case ShutdownType::on_shutdown: - { - std::lock_guard lock(on_shutdown_callbacks_mutex_); - on_shutdown_callbacks_.emplace(callback_shared_ptr); - } - break; + static_assert( + shutdown_type == ShutdownType::pre_shutdown || shutdown_type == ShutdownType::on_shutdown); + + if constexpr (shutdown_type == ShutdownType::pre_shutdown) { + std::lock_guard lock(pre_shutdown_callbacks_mutex_); + pre_shutdown_callbacks_.emplace(callback_shared_ptr); + } else { + std::lock_guard lock(on_shutdown_callbacks_mutex_); + on_shutdown_callbacks_.emplace(callback_shared_ptr); } ShutdownCallbackHandle callback_handle; @@ -415,73 +411,64 @@ Context::add_shutdown_callback( return callback_handle; } +template bool Context::remove_shutdown_callback( - ShutdownType shutdown_type, const ShutdownCallbackHandle & callback_handle) { - std::mutex * mutex_ptr = nullptr; - std::unordered_set< - std::shared_ptr> * callback_list_ptr; - - switch (shutdown_type) { - case ShutdownType::pre_shutdown: - mutex_ptr = &pre_shutdown_callbacks_mutex_; - callback_list_ptr = &pre_shutdown_callbacks_; - break; - case ShutdownType::on_shutdown: - mutex_ptr = &on_shutdown_callbacks_mutex_; - callback_list_ptr = &on_shutdown_callbacks_; - break; - } - - std::lock_guard lock(*mutex_ptr); - auto callback_shared_ptr = callback_handle.callback.lock(); + const auto callback_shared_ptr = callback_handle.callback.lock(); if (callback_shared_ptr == nullptr) { return false; } - return callback_list_ptr->erase(callback_shared_ptr) == 1; + + const auto remove_callback = [this, &callback_shared_ptr](auto & mutex, auto & callback_set) { + const std::lock_guard lock(mutex); + return callback_set.erase(callback_shared_ptr) == 1; + }; + + static_assert( + shutdown_type == ShutdownType::pre_shutdown || shutdown_type == ShutdownType::on_shutdown); + + if constexpr (shutdown_type == ShutdownType::pre_shutdown) { + return remove_callback(pre_shutdown_callbacks_mutex_, pre_shutdown_callbacks_); + } else { + return remove_callback(on_shutdown_callbacks_mutex_, on_shutdown_callbacks_); + } } std::vector Context::get_on_shutdown_callbacks() const { - return get_shutdown_callback(ShutdownType::on_shutdown); + return get_shutdown_callback(); } std::vector Context::get_pre_shutdown_callbacks() const { - return get_shutdown_callback(ShutdownType::pre_shutdown); + return get_shutdown_callback(); } +template std::vector -Context::get_shutdown_callback(ShutdownType shutdown_type) const +Context::get_shutdown_callback() const { - std::mutex * mutex_ptr = nullptr; - const std::unordered_set< - std::shared_ptr> * callback_list_ptr; - - switch (shutdown_type) { - case ShutdownType::pre_shutdown: - mutex_ptr = &pre_shutdown_callbacks_mutex_; - callback_list_ptr = &pre_shutdown_callbacks_; - break; - case ShutdownType::on_shutdown: - mutex_ptr = &on_shutdown_callbacks_mutex_; - callback_list_ptr = &on_shutdown_callbacks_; - break; - } + const auto get_callback_vector = [this](auto & mutex, auto & callback_set) { + const std::lock_guard lock(mutex); + std::vector callbacks; + for (auto & callback : callback_set) { + callbacks.push_back(*callback); + } + return callbacks; + }; - std::vector callbacks; - { - std::lock_guard lock(*mutex_ptr); - for (auto & iter : *callback_list_ptr) { - callbacks.emplace_back(*iter); - } - } + static_assert( + shutdown_type == ShutdownType::pre_shutdown || shutdown_type == ShutdownType::on_shutdown); - return callbacks; + if constexpr (shutdown_type == ShutdownType::pre_shutdown) { + return get_callback_vector(pre_shutdown_callbacks_mutex_, pre_shutdown_callbacks_); + } else { + return get_callback_vector(on_shutdown_callbacks_mutex_, on_shutdown_callbacks_); + } } std::shared_ptr diff --git a/rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp b/rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp index a62121b37f..3959e64882 100644 --- a/rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp +++ b/rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp @@ -51,18 +51,13 @@ rclcpp::detail::resolve_parameter_overrides( [params]() { rcl_yaml_node_struct_fini(params); }); - rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params); + rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params, node_fqn.c_str()); - // Enforce wildcard matching precedence - // TODO(cottsay) implement further wildcard matching - const std::array node_matching_names{"/**", node_fqn}; - for (const auto & node_name : node_matching_names) { - if (initial_map.count(node_name) > 0) { - // Combine parameter yaml files, overwriting values in older ones - for (const rclcpp::Parameter & param : initial_map.at(node_name)) { - result[param.get_name()] = - rclcpp::ParameterValue(param.get_value_message()); - } + if (initial_map.count(node_fqn) > 0) { + // Combine parameter yaml files, overwriting values in older ones + for (const rclcpp::Parameter & param : initial_map.at(node_fqn)) { + result[param.get_name()] = + rclcpp::ParameterValue(param.get_value_message()); } } } diff --git a/rclcpp/src/rclcpp/duration.cpp b/rclcpp/src/rclcpp/duration.cpp index 2966cc4899..2eac7f6b58 100644 --- a/rclcpp/src/rclcpp/duration.cpp +++ b/rclcpp/src/rclcpp/duration.cpp @@ -161,6 +161,13 @@ Duration::operator+(const rclcpp::Duration & rhs) const rcl_duration_.nanoseconds + rhs.rcl_duration_.nanoseconds); } +Duration & +Duration::operator+=(const rclcpp::Duration & rhs) +{ + *this = *this + rhs; + return *this; +} + void bounds_check_duration_difference(int64_t lhsns, int64_t rhsns, uint64_t max) { @@ -190,6 +197,13 @@ Duration::operator-(const rclcpp::Duration & rhs) const rcl_duration_.nanoseconds - rhs.rcl_duration_.nanoseconds); } +Duration & +Duration::operator-=(const rclcpp::Duration & rhs) +{ + *this = *this - rhs; + return *this; +} + void bounds_check_duration_scale(int64_t dns, double scale, uint64_t max) { @@ -222,6 +236,13 @@ Duration::operator*(double scale) const static_cast(rcl_duration_.nanoseconds) * scale_ld)); } +Duration & +Duration::operator*=(double scale) +{ + *this = *this * scale; + return *this; +} + rcl_duration_value_t Duration::nanoseconds() const { diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 73b7b8d80d..401beb0a73 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -106,11 +106,11 @@ Executor::~Executor() weak_groups_associated_with_executor_to_nodes_.clear(); weak_groups_to_nodes_associated_with_executor_.clear(); weak_groups_to_nodes_.clear(); - for (const auto & pair : weak_nodes_to_guard_conditions_) { + for (const auto & pair : weak_groups_to_guard_conditions_) { auto guard_condition = pair.second; memory_strategy_->remove_guard_condition(guard_condition); } - weak_nodes_to_guard_conditions_.clear(); + weak_groups_to_guard_conditions_.clear(); // Finalize the wait set. if (rcl_wait_set_fini(&wait_set_) != RCL_RET_OK) { @@ -204,8 +204,7 @@ Executor::add_callback_group_to_map( if (has_executor.exchange(true)) { throw std::runtime_error("Callback group has already been added to an executor."); } - bool is_new_node = !has_node(node_ptr, weak_groups_to_nodes_associated_with_executor_) && - !has_node(node_ptr, weak_groups_associated_with_executor_to_nodes_); + rclcpp::CallbackGroup::WeakPtr weak_group_ptr = group_ptr; auto insert_info = weak_groups_to_nodes.insert(std::make_pair(weak_group_ptr, node_ptr)); @@ -215,21 +214,24 @@ Executor::add_callback_group_to_map( } // Also add to the map that contains all callback groups weak_groups_to_nodes_.insert(std::make_pair(weak_group_ptr, node_ptr)); - if (is_new_node) { - const auto & gc = node_ptr->get_notify_guard_condition(); - weak_nodes_to_guard_conditions_[node_ptr] = &gc; - if (notify) { - // Interrupt waiting to handle new node - try { - interrupt_guard_condition_.trigger(); - } catch (const rclcpp::exceptions::RCLError & ex) { - throw std::runtime_error( - std::string( - "Failed to trigger guard condition on callback group add: ") + ex.what()); - } + + if (node_ptr->get_context()->is_valid()) { + auto callback_group_guard_condition = + group_ptr->get_notify_guard_condition(node_ptr->get_context()); + weak_groups_to_guard_conditions_[weak_group_ptr] = callback_group_guard_condition.get(); + // Add the callback_group's notify condition to the guard condition handles + memory_strategy_->add_guard_condition(*callback_group_guard_condition); + } + + if (notify) { + // Interrupt waiting to handle new node + try { + interrupt_guard_condition_.trigger(); + } catch (const rclcpp::exceptions::RCLError & ex) { + throw std::runtime_error( + std::string( + "Failed to trigger guard condition on callback group add: ") + ex.what()); } - // Add the node's notify condition to the guard condition handles - memory_strategy_->add_guard_condition(gc); } } @@ -300,7 +302,12 @@ Executor::remove_callback_group_from_map( if (!has_node(node_ptr, weak_groups_to_nodes_associated_with_executor_) && !has_node(node_ptr, weak_groups_associated_with_executor_to_nodes_)) { - weak_nodes_to_guard_conditions_.erase(node_ptr); + auto iter = weak_groups_to_guard_conditions_.find(weak_group_ptr); + if (iter != weak_groups_to_guard_conditions_.end()) { + memory_strategy_->remove_guard_condition(iter->second); + } + weak_groups_to_guard_conditions_.erase(weak_group_ptr); + if (notify) { try { interrupt_guard_condition_.trigger(); @@ -310,7 +317,6 @@ Executor::remove_callback_group_from_map( "Failed to trigger guard condition on callback group remove: ") + ex.what()); } } - memory_strategy_->remove_guard_condition(&node_ptr->get_notify_guard_condition()); } } @@ -700,12 +706,6 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout) auto weak_node_ptr = pair.second; if (weak_group_ptr.expired() || weak_node_ptr.expired()) { invalid_group_ptrs.push_back(weak_group_ptr); - auto node_guard_pair = weak_nodes_to_guard_conditions_.find(weak_node_ptr); - if (node_guard_pair != weak_nodes_to_guard_conditions_.end()) { - auto guard_condition = node_guard_pair->second; - weak_nodes_to_guard_conditions_.erase(weak_node_ptr); - memory_strategy_->remove_guard_condition(guard_condition); - } } } std::for_each( @@ -721,6 +721,12 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout) { weak_groups_associated_with_executor_to_nodes_.erase(group_ptr); } + auto callback_guard_pair = weak_groups_to_guard_conditions_.find(group_ptr); + if (callback_guard_pair != weak_groups_to_guard_conditions_.end()) { + auto guard_condition = callback_guard_pair->second; + weak_groups_to_guard_conditions_.erase(group_ptr); + memory_strategy_->remove_guard_condition(guard_condition); + } weak_groups_to_nodes_.erase(group_ptr); }); } diff --git a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp index bb477690be..507d47f913 100644 --- a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp @@ -21,6 +21,7 @@ #include "rcpputils/scope_exit.hpp" +#include "rclcpp/logging.hpp" #include "rclcpp/utilities.hpp" using rclcpp::executors::MultiThreadedExecutor; @@ -34,9 +35,15 @@ MultiThreadedExecutor::MultiThreadedExecutor( yield_before_execute_(yield_before_execute), next_exec_timeout_(next_exec_timeout) { - number_of_threads_ = number_of_threads ? number_of_threads : std::thread::hardware_concurrency(); - if (number_of_threads_ == 0) { - number_of_threads_ = 1; + number_of_threads_ = number_of_threads > 0 ? + number_of_threads : + std::max(std::thread::hardware_concurrency(), 2U); + + if (number_of_threads_ == 1) { + RCLCPP_WARN( + rclcpp::get_logger("rclcpp"), + "MultiThreadedExecutor is used with a single thread.\n" + "Use the SingleThreadedExecutor instead."); } } diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index 8107458f43..c1fbdb1f98 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -176,7 +176,8 @@ Node::Node( node_topics_, node_graph_, node_services_, - node_logging_ + node_logging_, + options.clock_type() )), node_parameters_(new rclcpp::node_interfaces::NodeParameters( node_base_, @@ -353,7 +354,7 @@ Node::has_parameter(const std::string & name) const rcl_interfaces::msg::SetParametersResult Node::set_parameter(const rclcpp::Parameter & parameter) { - return this->set_parameters_atomically({parameter}); + return node_parameters_->set_parameters_atomically({parameter}); } std::vector @@ -418,16 +419,40 @@ Node::list_parameters(const std::vector & prefixes, uint64_t depth) return node_parameters_->list_parameters(prefixes, depth); } +rclcpp::Node::PreSetParametersCallbackHandle::SharedPtr +Node::add_pre_set_parameters_callback(PreSetParametersCallbackType callback) +{ + return node_parameters_->add_pre_set_parameters_callback(callback); +} + rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr -Node::add_on_set_parameters_callback(OnParametersSetCallbackType callback) +Node::add_on_set_parameters_callback(OnSetParametersCallbackType callback) { return node_parameters_->add_on_set_parameters_callback(callback); } +rclcpp::Node::PostSetParametersCallbackHandle::SharedPtr +Node::add_post_set_parameters_callback(PostSetParametersCallbackType callback) +{ + return node_parameters_->add_post_set_parameters_callback(callback); +} + +void +Node::remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle * const handler) +{ + node_parameters_->remove_pre_set_parameters_callback(handler); +} + +void +Node::remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler) +{ + node_parameters_->remove_on_set_parameters_callback(handler); +} + void -Node::remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const callback) +Node::remove_post_set_parameters_callback(const PostSetParametersCallbackHandle * const handler) { - return node_parameters_->remove_on_set_parameters_callback(callback); + node_parameters_->remove_post_set_parameters_callback(handler); } std::vector diff --git a/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp b/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp index 734d7bdb37..a37c65b71b 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_clock.cpp @@ -24,13 +24,14 @@ NodeClock::NodeClock( rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services, - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging) + rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, + rcl_clock_type_t clock_type) : node_base_(node_base), node_topics_(node_topics), node_graph_(node_graph), node_services_(node_services), node_logging_(node_logging), - ros_clock_(std::make_shared(RCL_ROS_TIME)) + clock_(std::make_shared(clock_type)) {} NodeClock::~NodeClock() @@ -39,11 +40,11 @@ NodeClock::~NodeClock() rclcpp::Clock::SharedPtr NodeClock::get_clock() { - return ros_clock_; + return clock_; } rclcpp::Clock::ConstSharedPtr NodeClock::get_clock() const { - return ros_clock_; + return clock_; } diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 0f366792b7..9dafcba381 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -305,18 +305,54 @@ __check_parameters( return result; } -using OnParametersSetCallbackType = - rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType; -using CallbacksContainerType = - rclcpp::node_interfaces::NodeParameters::CallbacksContainerType; +using PreSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType; +using PreSetParametersCallbackHandle = + rclcpp::node_interfaces::PreSetParametersCallbackHandle; +using PreSetCallbacksHandleContainer = + rclcpp::node_interfaces::NodeParameters::PreSetCallbacksHandleContainer; + +using OnSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType; using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle; +using OnSetCallbacksHandleContainer = + rclcpp::node_interfaces::NodeParameters::OnSetCallbacksHandleContainer; + +using PostSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType; +using PostSetParametersCallbackHandle = + rclcpp::node_interfaces::PostSetParametersCallbackHandle; +using PostSetCallbacksHandleContainer = + rclcpp::node_interfaces::NodeParameters::PostSetCallbacksHandleContainer; + +RCLCPP_LOCAL +void +__call_pre_set_parameters_callbacks( + std::vector & parameters, + PreSetCallbacksHandleContainer & callback_container) +{ + if (callback_container.empty()) { + return; + } + + auto it = callback_container.begin(); + while (it != callback_container.end()) { + auto shared_handle = it->lock(); + if (nullptr != shared_handle) { + shared_handle->callback(parameters); + it++; + } else { + it = callback_container.erase(it); + } + } +} RCLCPP_LOCAL rcl_interfaces::msg::SetParametersResult -__call_on_parameters_set_callbacks( +__call_on_set_parameters_callbacks( const std::vector & parameters, - CallbacksContainerType & callback_container) + OnSetCallbacksHandleContainer & callback_container) { rcl_interfaces::msg::SetParametersResult result; result.successful = true; @@ -336,12 +372,34 @@ __call_on_parameters_set_callbacks( return result; } +RCLCPP_LOCAL +void __call_post_set_parameters_callbacks( + const std::vector & parameters, + PostSetCallbacksHandleContainer & callback_container) +{ + if (callback_container.empty()) { + return; + } + + auto it = callback_container.begin(); + while (it != callback_container.end()) { + auto shared_handle = it->lock(); + if (nullptr != shared_handle) { + shared_handle->callback(parameters); + it++; + } else { + it = callback_container.erase(it); + } + } +} + RCLCPP_LOCAL rcl_interfaces::msg::SetParametersResult __set_parameters_atomically_common( const std::vector & parameters, std::map & parameter_infos, - CallbacksContainerType & callback_container, + OnSetCallbacksHandleContainer & on_set_callback_container, + PostSetCallbacksHandleContainer & post_set_callback_container, bool allow_undeclared = false) { // Check if the value being set complies with the descriptor. @@ -352,7 +410,7 @@ __set_parameters_atomically_common( } // Call the user callbacks to see if the new value(s) are allowed. result = - __call_on_parameters_set_callbacks(parameters, callback_container); + __call_on_set_parameters_callbacks(parameters, on_set_callback_container); if (!result.successful) { return result; } @@ -364,6 +422,8 @@ __set_parameters_atomically_common( parameter_infos[name].descriptor.type = parameters[i].get_type(); parameter_infos[name].value = parameters[i].get_parameter_value(); } + // Call the user post set parameter callback + __call_post_set_parameters_callbacks(parameters, post_set_callback_container); } // Either way, return the result. @@ -378,7 +438,8 @@ __declare_parameter_common( const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor, std::map & parameters_out, const std::map & overrides, - CallbacksContainerType & callback_container, + OnSetCallbacksHandleContainer & on_set_callback_container, + PostSetCallbacksHandleContainer & post_set_callback_container, rcl_interfaces::msg::ParameterEvent * parameter_event_out, bool ignore_override = false) { @@ -414,7 +475,9 @@ __declare_parameter_common( auto result = __set_parameters_atomically_common( parameter_wrappers, parameter_infos, - callback_container); + on_set_callback_container, + post_set_callback_container + ); if (!result.successful) { return result; @@ -441,7 +504,8 @@ declare_parameter_helper( bool ignore_override, std::map & parameters, const std::map & overrides, - CallbacksContainerType & callback_container, + OnSetCallbacksHandleContainer & on_set_callback_container, + PostSetCallbacksHandleContainer & post_set_callback_container, rclcpp::Publisher * events_publisher, const std::string & combined_name, rclcpp::node_interfaces::NodeClockInterface & node_clock) @@ -477,7 +541,8 @@ declare_parameter_helper( parameter_descriptor, parameters, overrides, - callback_container, + on_set_callback_container, + post_set_callback_container, ¶meter_event, ignore_override); @@ -524,7 +589,8 @@ NodeParameters::declare_parameter( ignore_override, parameters_, parameter_overrides_, - on_parameters_set_callback_container_, + on_set_parameters_callback_container_, + post_set_parameters_callback_container_, events_publisher_.get(), combined_name_, *node_clock_); @@ -559,7 +625,8 @@ NodeParameters::declare_parameter( ignore_override, parameters_, parameter_overrides_, - on_parameters_set_callback_container_, + on_set_parameters_callback_container_, + post_set_parameters_callback_container_, events_publisher_.get(), combined_name_, *node_clock_); @@ -633,12 +700,27 @@ NodeParameters::set_parameters_atomically(const std::vector & rcl_interfaces::msg::SetParametersResult result; + // call any user registered pre set parameter callbacks + // this callback can make changes to the original parameters list + // also check if the changed parameter list is empty or not, if empty return + std::vector parameters_after_pre_set_callback(parameters); + __call_pre_set_parameters_callbacks( + parameters_after_pre_set_callback, + pre_set_parameters_callback_container_); + + if (parameters_after_pre_set_callback.empty()) { + result.successful = false; + result.reason = "parameter list cannot be empty, this might be due to " + "pre_set_parameters_callback modifying the original parameters list."; + return result; + } + // Check if any of the parameters are read-only, or if any parameters are not // declared. // If not declared, keep track of them in order to declare them later, when // undeclared parameters are allowed, and if they're not allowed, fail. std::vector parameters_to_be_declared; - for (const auto & parameter : parameters) { + for (const auto & parameter : parameters_after_pre_set_callback) { const std::string & name = parameter.get_name(); // Check to make sure the parameter name is valid. @@ -678,7 +760,8 @@ NodeParameters::set_parameters_atomically(const std::vector & std::map staged_parameter_changes; rcl_interfaces::msg::ParameterEvent parameter_event_msg; parameter_event_msg.node = combined_name_; - CallbacksContainerType empty_callback_container; + OnSetCallbacksHandleContainer empty_on_set_callback_container; + PostSetCallbacksHandleContainer empty_post_set_callback_container; // Implicit declare uses dynamic type descriptor. rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -693,7 +776,8 @@ NodeParameters::set_parameters_atomically(const std::vector & staged_parameter_changes, parameter_overrides_, // Only call callbacks once below - empty_callback_container, // callback_container is explicitly empty + empty_on_set_callback_container, // callback_container is explicitly empty + empty_post_set_callback_container, // callback_container is explicitly empty ¶meter_event_msg, true); if (!result.successful) { @@ -706,12 +790,14 @@ NodeParameters::set_parameters_atomically(const std::vector & // If there were implicitly declared parameters, then we may need to copy the input parameters // and then assign the value that was selected after the declare (could be affected by the // initial parameter values). - const std::vector * parameters_to_be_set = ¶meters; + const std::vector * parameters_to_be_set = ¶meters_after_pre_set_callback; std::vector parameters_copy; if (0 != staged_parameter_changes.size()) { // If there were any implicitly declared parameters. bool any_initial_values_used = false; for (const auto & staged_parameter_change : staged_parameter_changes) { - auto it = __find_parameter_by_name(parameters, staged_parameter_change.first); + auto it = __find_parameter_by_name( + parameters_after_pre_set_callback, + staged_parameter_change.first); if (it->get_parameter_value() != staged_parameter_change.second.value) { // In this case, the value of the staged parameter differs from the // input from the user, and therefore we need to update things before setting. @@ -721,7 +807,7 @@ NodeParameters::set_parameters_atomically(const std::vector & } } if (any_initial_values_used) { - parameters_copy = parameters; + parameters_copy = parameters_after_pre_set_callback; for (const auto & staged_parameter_change : staged_parameter_changes) { auto it = __find_parameter_by_name(parameters_copy, staged_parameter_change.first); *it = Parameter(staged_parameter_change.first, staged_parameter_change.second.value); @@ -754,8 +840,9 @@ NodeParameters::set_parameters_atomically(const std::vector & // they are actually set on the official parameter storage parameters_, // These callbacks are called once. When a callback returns an unsuccessful result, - // the remaining aren't called. - on_parameters_set_callback_container_, + // the remaining aren't called + on_set_parameters_callback_container_, + post_set_parameters_callback_container_, allow_undeclared_); // allow undeclared // If not successful, then stop here. @@ -811,29 +898,18 @@ NodeParameters::set_parameters_atomically(const std::vector & parameter_event_msg.stamp = node_clock_->get_clock()->now(); events_publisher_->publish(parameter_event_msg); } - return result; } std::vector NodeParameters::get_parameters(const std::vector & names) const { - std::lock_guard lock(mutex_); std::vector results; results.reserve(names.size()); + std::lock_guard lock(mutex_); for (auto & name : names) { - auto found_parameter = parameters_.find(name); - if (found_parameter != parameters_.cend()) { - // found - results.emplace_back(name, found_parameter->second.value); - } else if (this->allow_undeclared_) { - // not found, but undeclared allowed - results.emplace_back(name, rclcpp::ParameterValue()); - } else { - // not found, and undeclared are not allowed - throw rclcpp::exceptions::ParameterNotDeclaredException(name); - } + results.emplace_back(this->get_parameter(name)); } return results; } @@ -844,18 +920,18 @@ NodeParameters::get_parameter(const std::string & name) const std::lock_guard lock(mutex_); auto param_iter = parameters_.find(name); - if ( - parameters_.end() != param_iter && - (param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET || - param_iter->second.descriptor.dynamic_typing)) - { - return rclcpp::Parameter{name, param_iter->second.value}; + if (parameters_.end() != param_iter) { + if ( + param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET || + param_iter->second.descriptor.dynamic_typing) + { + return rclcpp::Parameter{name, param_iter->second.value}; + } + throw rclcpp::exceptions::ParameterUninitializedException(name); } else if (this->allow_undeclared_) { - return rclcpp::Parameter{}; - } else if (parameters_.end() == param_iter) { - throw rclcpp::exceptions::ParameterNotDeclaredException(name); + return rclcpp::Parameter{name}; } else { - throw rclcpp::exceptions::ParameterUninitializedException(name); + throw rclcpp::exceptions::ParameterNotDeclaredException(name); } } @@ -997,6 +1073,26 @@ NodeParameters::list_parameters(const std::vector & prefixes, uint6 return result; } +void +NodeParameters::remove_pre_set_parameters_callback( + const PreSetParametersCallbackHandle * const handle) +{ + std::lock_guard lock(mutex_); + ParameterMutationRecursionGuard guard(parameter_modification_enabled_); + + auto it = std::find_if( + pre_set_parameters_callback_container_.begin(), + pre_set_parameters_callback_container_.end(), + [handle](const auto & weak_handle) { + return handle == weak_handle.lock().get(); + }); + if (it != pre_set_parameters_callback_container_.end()) { + pre_set_parameters_callback_container_.erase(it); + } else { + throw std::runtime_error("Pre set parameter callback doesn't exist"); + } +} + void NodeParameters::remove_on_set_parameters_callback( const OnSetParametersCallbackHandle * const handle) @@ -1005,20 +1101,53 @@ NodeParameters::remove_on_set_parameters_callback( ParameterMutationRecursionGuard guard(parameter_modification_enabled_); auto it = std::find_if( - on_parameters_set_callback_container_.begin(), - on_parameters_set_callback_container_.end(), + on_set_parameters_callback_container_.begin(), + on_set_parameters_callback_container_.end(), [handle](const auto & weak_handle) { return handle == weak_handle.lock().get(); }); - if (it != on_parameters_set_callback_container_.end()) { - on_parameters_set_callback_container_.erase(it); + if (it != on_set_parameters_callback_container_.end()) { + on_set_parameters_callback_container_.erase(it); } else { - throw std::runtime_error("Callback doesn't exist"); + throw std::runtime_error("On set parameter callback doesn't exist"); } } +void +NodeParameters::remove_post_set_parameters_callback( + const PostSetParametersCallbackHandle * const handle) +{ + std::lock_guard lock(mutex_); + ParameterMutationRecursionGuard guard(parameter_modification_enabled_); + + auto it = std::find_if( + post_set_parameters_callback_container_.begin(), + post_set_parameters_callback_container_.end(), + [handle](const auto & weak_handle) { + return handle == weak_handle.lock().get(); + }); + if (it != post_set_parameters_callback_container_.end()) { + post_set_parameters_callback_container_.erase(it); + } else { + throw std::runtime_error("Post set parameter callback doesn't exist"); + } +} + +PreSetParametersCallbackHandle::SharedPtr +NodeParameters::add_pre_set_parameters_callback(PreSetParametersCallbackType callback) +{ + std::lock_guard lock(mutex_); + ParameterMutationRecursionGuard guard(parameter_modification_enabled_); + + auto handle = std::make_shared(); + handle->callback = callback; + // the last callback registered is executed first. + pre_set_parameters_callback_container_.emplace_front(handle); + return handle; +} + OnSetParametersCallbackHandle::SharedPtr -NodeParameters::add_on_set_parameters_callback(OnParametersSetCallbackType callback) +NodeParameters::add_on_set_parameters_callback(OnSetParametersCallbackType callback) { std::lock_guard lock(mutex_); ParameterMutationRecursionGuard guard(parameter_modification_enabled_); @@ -1026,7 +1155,21 @@ NodeParameters::add_on_set_parameters_callback(OnParametersSetCallbackType callb auto handle = std::make_shared(); handle->callback = callback; // the last callback registered is executed first. - on_parameters_set_callback_container_.emplace_front(handle); + on_set_parameters_callback_container_.emplace_front(handle); + return handle; +} + +PostSetParametersCallbackHandle::SharedPtr +NodeParameters::add_post_set_parameters_callback( + PostSetParametersCallbackType callback) +{ + std::lock_guard lock(mutex_); + ParameterMutationRecursionGuard guard(parameter_modification_enabled_); + + auto handle = std::make_shared(); + handle->callback = callback; + // the last callback registered is executed first. + post_set_parameters_callback_container_.emplace_front(handle); return handle; } diff --git a/rclcpp/src/rclcpp/node_interfaces/node_services.cpp b/rclcpp/src/rclcpp/node_interfaces/node_services.cpp index 14ab1c82c4..2f1afd3224 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_services.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_services.cpp @@ -35,15 +35,17 @@ NodeServices::add_service( // TODO(jacquelinekay): use custom exception throw std::runtime_error("Cannot create service, group not in node."); } - group->add_service(service_base_ptr); } else { - node_base_->get_default_callback_group()->add_service(service_base_ptr); + group = node_base_->get_default_callback_group(); } + group->add_service(service_base_ptr); + // Notify the executor that a new service was created using the parent Node. auto & node_gc = node_base_->get_notify_guard_condition(); try { node_gc.trigger(); + group->trigger_notify_guard_condition(); } catch (const rclcpp::exceptions::RCLError & ex) { throw std::runtime_error( std::string("failed to notify wait set on service creation: ") + ex.what()); @@ -60,15 +62,17 @@ NodeServices::add_client( // TODO(jacquelinekay): use custom exception throw std::runtime_error("Cannot create client, group not in node."); } - group->add_client(client_base_ptr); } else { - node_base_->get_default_callback_group()->add_client(client_base_ptr); + group = node_base_->get_default_callback_group(); } + group->add_client(client_base_ptr); + // Notify the executor that a new client was created using the parent Node. auto & node_gc = node_base_->get_notify_guard_condition(); try { node_gc.trigger(); + group->trigger_notify_guard_condition(); } catch (const rclcpp::exceptions::RCLError & ex) { throw std::runtime_error( std::string("failed to notify wait set on client creation: ") + ex.what()); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp index b463e8a0e7..d2e821a9e6 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp @@ -37,14 +37,15 @@ NodeTimers::add_timer( // TODO(jacquelinekay): use custom exception throw std::runtime_error("Cannot create timer, group not in node."); } - callback_group->add_timer(timer); } else { - node_base_->get_default_callback_group()->add_timer(timer); + callback_group = node_base_->get_default_callback_group(); } + callback_group->add_timer(timer); auto & node_gc = node_base_->get_notify_guard_condition(); try { node_gc.trigger(); + callback_group->trigger_notify_guard_condition(); } catch (const rclcpp::exceptions::RCLError & ex) { throw std::runtime_error( std::string("failed to notify wait set on timer creation: ") + ex.what()); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp b/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp index 159409528d..167a35f35d 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp @@ -73,6 +73,7 @@ NodeTopics::add_publisher( auto & node_gc = node_base_->get_notify_guard_condition(); try { node_gc.trigger(); + callback_group->trigger_notify_guard_condition(); } catch (const rclcpp::exceptions::RCLError & ex) { throw std::runtime_error( std::string("failed to notify wait set on publisher creation: ") + ex.what()); @@ -121,6 +122,7 @@ NodeTopics::add_subscription( auto & node_gc = node_base_->get_notify_guard_condition(); try { node_gc.trigger(); + callback_group->trigger_notify_guard_condition(); } catch (const rclcpp::exceptions::RCLError & ex) { throw std::runtime_error( std::string("failed to notify wait set on subscription creation: ") + ex.what()); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp b/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp index 6f243f6025..1d1fe2ce59 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp @@ -35,15 +35,17 @@ NodeWaitables::add_waitable( // TODO(jacobperron): use custom exception throw std::runtime_error("Cannot create waitable, group not in node."); } - group->add_waitable(waitable_ptr); } else { - node_base_->get_default_callback_group()->add_waitable(waitable_ptr); + group = node_base_->get_default_callback_group(); } + group->add_waitable(waitable_ptr); + // Notify the executor that a new waitable was created using the parent Node. auto & node_gc = node_base_->get_notify_guard_condition(); try { node_gc.trigger(); + group->trigger_notify_guard_condition(); } catch (const rclcpp::exceptions::RCLError & ex) { throw std::runtime_error( std::string("failed to notify wait set on waitable creation: ") + ex.what()); diff --git a/rclcpp/src/rclcpp/node_options.cpp b/rclcpp/src/rclcpp/node_options.cpp index 06feffd1e6..b90a4b27e7 100644 --- a/rclcpp/src/rclcpp/node_options.cpp +++ b/rclcpp/src/rclcpp/node_options.cpp @@ -77,6 +77,7 @@ NodeOptions::operator=(const NodeOptions & other) this->enable_topic_statistics_ = other.enable_topic_statistics_; this->start_parameter_services_ = other.start_parameter_services_; this->start_parameter_event_publisher_ = other.start_parameter_event_publisher_; + this->clock_type_ = other.clock_type_; this->clock_qos_ = other.clock_qos_; this->use_clock_thread_ = other.use_clock_thread_; this->parameter_event_qos_ = other.parameter_event_qos_; @@ -260,6 +261,19 @@ NodeOptions::start_parameter_event_publisher(bool start_parameter_event_publishe return *this; } +const rcl_clock_type_t & +NodeOptions::clock_type() const +{ + return this->clock_type_; +} + +NodeOptions & +NodeOptions::clock_type(const rcl_clock_type_t & clock_type) +{ + this->clock_type_ = clock_type; + return *this; +} + const rclcpp::QoS & NodeOptions::clock_qos() const { diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index c8c4d50f35..2d3488e7d1 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -35,7 +35,7 @@ AsyncParametersClient::AsyncParametersClient( const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile, + const rclcpp::QoS & qos_profile, rclcpp::CallbackGroup::SharedPtr group) : node_topics_interface_(node_topics_interface) { @@ -46,7 +46,7 @@ AsyncParametersClient::AsyncParametersClient( } rcl_client_options_t options = rcl_client_get_default_options(); - options.qos = qos_profile; + options.qos = qos_profile.get_rmw_qos_profile(); using rclcpp::Client; using rclcpp::ClientBase; @@ -290,28 +290,24 @@ std::shared_future> AsyncParametersClient::load_parameters( const std::string & yaml_filename) { - rclcpp::ParameterMap parameter_map = rclcpp::parameter_map_from_yaml_file(yaml_filename); - return this->load_parameters(parameter_map); + rclcpp::ParameterMap parameter_map = + rclcpp::parameter_map_from_yaml_file(yaml_filename, remote_node_name_.c_str()); + + auto iter = parameter_map.find(remote_node_name_); + if (iter == parameter_map.end() || iter->second.size() == 0) { + throw rclcpp::exceptions::InvalidParametersException("No valid parameter"); + } + auto future_result = set_parameters(iter->second); + + return future_result; } std::shared_future> AsyncParametersClient::load_parameters( const rclcpp::ParameterMap & parameter_map) { - std::vector parameters; - std::string remote_name = remote_node_name_.substr(remote_node_name_.substr(1).find("/") + 2); - for (const auto & params : parameter_map) { - std::string node_full_name = params.first; - std::string node_name = node_full_name.substr(node_full_name.find("/*/") + 3); - if (node_full_name == remote_node_name_ || - node_full_name == "/**" || - (node_name == remote_name)) - { - for (const auto & param : params.second) { - parameters.push_back(param); - } - } - } + std::vector parameters = + rclcpp::parameters_from_map(parameter_map, remote_node_name_.c_str()); if (parameters.size() == 0) { throw rclcpp::exceptions::InvalidParametersException("No valid parameter"); diff --git a/rclcpp/src/rclcpp/parameter_map.cpp b/rclcpp/src/rclcpp/parameter_map.cpp index e5e3da019c..5ed67daae6 100644 --- a/rclcpp/src/rclcpp/parameter_map.cpp +++ b/rclcpp/src/rclcpp/parameter_map.cpp @@ -13,8 +13,11 @@ // limitations under the License. #include +#include #include +#include "rcpputils/find_and_replace.hpp" +#include "rcpputils/scope_exit.hpp" #include "rclcpp/parameter_map.hpp" using rclcpp::exceptions::InvalidParametersException; @@ -22,8 +25,15 @@ using rclcpp::exceptions::InvalidParameterValueException; using rclcpp::ParameterMap; using rclcpp::ParameterValue; +static bool is_node_name_matched(const std::string & node_name, const char * node_fqn) +{ + // Update the regular expression ["/*" -> "(/\\w+)" and "/**" -> "(/\\w+)*"] + std::string regex = rcpputils::find_and_replace(node_name, "/*", "(/\\w+)"); + return std::regex_match(node_fqn, std::regex(regex)); +} + ParameterMap -rclcpp::parameter_map_from(const rcl_params_t * const c_params) +rclcpp::parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn) { if (NULL == c_params) { throw InvalidParametersException("parameters struct is NULL"); @@ -49,6 +59,15 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params) node_name = c_node_name; } + if (node_fqn) { + if (!is_node_name_matched(node_name, node_fqn)) { + // No need to parse the items because the user just care about node_fqn + continue; + } + + node_name = node_fqn; + } + const rcl_node_params_t * const c_params_node = &(c_params->params[n]); std::vector & params_node = parameters[node_name]; @@ -65,6 +84,7 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params) params_node.emplace_back(c_param_name, parameter_value_from(c_param_value)); } } + return parameters; } @@ -128,13 +148,31 @@ rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value) } ParameterMap -rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename) +rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename, const char * node_fqn) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rcl_params_t * rcl_parameters = rcl_yaml_node_struct_init(allocator); + RCPPUTILS_SCOPE_EXIT(rcl_yaml_node_struct_fini(rcl_parameters); ); const char * path = yaml_filename.c_str(); if (!rcl_parse_yaml_file(path, rcl_parameters)) { rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR); } - return rclcpp::parameter_map_from(rcl_parameters); + + return rclcpp::parameter_map_from(rcl_parameters, node_fqn); +} + +std::vector +rclcpp::parameters_from_map(const ParameterMap & parameter_map, const char * node_fqn) +{ + std::vector parameters; + std::string node_name_old; + for (auto & [node_name, node_parameters] : parameter_map) { + if (node_fqn && !is_node_name_matched(node_name, node_fqn)) { + // No need to parse the items because the user just care about node_fqn + continue; + } + parameters.insert(parameters.end(), node_parameters.begin(), node_parameters.end()); + } + + return parameters; } diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index 5c30917499..0923798339 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -29,7 +29,7 @@ ParameterService::ParameterService( const std::shared_ptr node_base, const std::shared_ptr node_services, rclcpp::node_interfaces::NodeParametersInterface * node_params, - const rmw_qos_profile_t & qos_profile) + const rclcpp::QoS & qos_profile) { const std::string node_name = node_base->get_name(); @@ -48,6 +48,8 @@ ParameterService::ParameterService( } } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); + } catch (const rclcpp::exceptions::ParameterUninitializedException & ex) { + RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); } }, qos_profile, nullptr); diff --git a/rclcpp/src/rclcpp/publisher_base.cpp b/rclcpp/src/rclcpp/publisher_base.cpp index 723d56e0d5..ce0540659a 100644 --- a/rclcpp/src/rclcpp/publisher_base.cpp +++ b/rclcpp/src/rclcpp/publisher_base.cpp @@ -45,11 +45,14 @@ PublisherBase::PublisherBase( rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic, const rosidl_message_type_support_t & type_support, - const rcl_publisher_options_t & publisher_options) + const rcl_publisher_options_t & publisher_options, + const PublisherEventCallbacks & event_callbacks, + bool use_default_callbacks) : rcl_node_handle_(node_base->get_shared_rcl_node_handle()), intra_process_is_enabled_(false), intra_process_publisher_id_(0), - type_support_(type_support) + type_support_(type_support), + event_callbacks_(event_callbacks) { auto custom_deleter = [node_handle = this->rcl_node_handle_](rcl_publisher_t * rcl_pub) { @@ -98,15 +101,12 @@ PublisherBase::PublisherBase( rmw_reset_error(); throw std::runtime_error(msg); } + + bind_event_callbacks(event_callbacks_, use_default_callbacks); } PublisherBase::~PublisherBase() { - for (const auto & pair : event_handlers_) { - rcl_publisher_event_type_t event_type = pair.first; - clear_on_new_qos_event_callback(event_type); - } - // must fini the events before fini-ing the publisher event_handlers_.clear(); @@ -131,6 +131,38 @@ PublisherBase::get_topic_name() const return rcl_publisher_get_topic_name(publisher_handle_.get()); } +void +PublisherBase::bind_event_callbacks( + const PublisherEventCallbacks & event_callbacks, bool use_default_callbacks) +{ + if (event_callbacks.deadline_callback) { + this->add_event_handler( + event_callbacks.deadline_callback, + RCL_PUBLISHER_OFFERED_DEADLINE_MISSED); + } + if (event_callbacks.liveliness_callback) { + this->add_event_handler( + event_callbacks.liveliness_callback, + RCL_PUBLISHER_LIVELINESS_LOST); + } + if (event_callbacks.incompatible_qos_callback) { + this->add_event_handler( + event_callbacks.incompatible_qos_callback, + RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS); + } else if (use_default_callbacks) { + // Register default callback when not specified + try { + this->add_event_handler( + [this](QOSOfferedIncompatibleQoSInfo & info) { + this->default_incompatible_qos_callback(info); + }, + RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS); + } catch (UnsupportedEventTypeException & /*exc*/) { + // pass + } + } +} + size_t PublisherBase::get_queue_size() const { diff --git a/rclcpp/src/rclcpp/qos.cpp b/rclcpp/src/rclcpp/qos.cpp index 70b9976db6..2453149aa4 100644 --- a/rclcpp/src/rclcpp/qos.cpp +++ b/rclcpp/src/rclcpp/qos.cpp @@ -16,6 +16,8 @@ #include +#include "rclcpp/logging.hpp" + #include "rmw/error_handling.h" #include "rmw/types.h" #include "rmw/qos_profiles.h" @@ -43,9 +45,19 @@ std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind) } } -QoSInitialization::QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg) +QoSInitialization::QoSInitialization( + rmw_qos_history_policy_t history_policy_arg, size_t depth_arg, + bool print_depth_warning) : history_policy(history_policy_arg), depth(depth_arg) -{} +{ + if (history_policy == RMW_QOS_POLICY_HISTORY_KEEP_LAST && depth == 0 && print_depth_warning) { + RCLCPP_WARN_ONCE( + rclcpp::get_logger( + "rclcpp"), + "A zero depth with KEEP_LAST doesn't make sense; no data could be stored. " + "This will be interpreted as SYSTEM_DEFAULT"); + } +} QoSInitialization QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos) @@ -53,8 +65,9 @@ QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos) switch (rmw_qos.history) { case RMW_QOS_POLICY_HISTORY_KEEP_ALL: return KeepAll(); - case RMW_QOS_POLICY_HISTORY_KEEP_LAST: case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT: + return KeepLast(rmw_qos.depth, false); + case RMW_QOS_POLICY_HISTORY_KEEP_LAST: case RMW_QOS_POLICY_HISTORY_UNKNOWN: default: return KeepLast(rmw_qos.depth); @@ -65,9 +78,10 @@ KeepAll::KeepAll() : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 0) {} -KeepLast::KeepLast(size_t depth) -: QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth) -{} +KeepLast::KeepLast(size_t depth, bool print_depth_warning) +: QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth, print_depth_warning) +{ +} QoS::QoS( const QoSInitialization & qos_initialization, @@ -111,6 +125,14 @@ QoS::history(HistoryPolicy history) QoS & QoS::keep_last(size_t depth) { + if (depth == 0) { + RCLCPP_WARN_ONCE( + rclcpp::get_logger( + "rclcpp"), + "A zero depth with KEEP_LAST doesn't make sense; no data could be stored." + "This will be interpreted as SYSTEM_DEFAULT"); + } + rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST; rmw_qos_profile_.depth = depth; return *this; diff --git a/rclcpp/src/rclcpp/qos_event.cpp b/rclcpp/src/rclcpp/qos_event.cpp index 8bfd5b3304..91df5bb346 100644 --- a/rclcpp/src/rclcpp/qos_event.cpp +++ b/rclcpp/src/rclcpp/qos_event.cpp @@ -35,6 +35,11 @@ UnsupportedEventTypeException::UnsupportedEventTypeException( QOSEventHandlerBase::~QOSEventHandlerBase() { + // Since the rmw event listener holds a reference to + // this callback, we need to clear it on destruction of this class. + // This clearing is not needed for other rclcpp entities like pub/subs, since + // they do own the underlying rmw entities, which are destroyed + // on their rclcpp destructors, thus no risk of dangling pointers. if (on_new_event_callback_) { clear_on_ready_callback(); } diff --git a/rclcpp/src/rclcpp/service.cpp b/rclcpp/src/rclcpp/service.cpp index 7bc580ce68..ea1a83a2a6 100644 --- a/rclcpp/src/rclcpp/service.cpp +++ b/rclcpp/src/rclcpp/service.cpp @@ -32,10 +32,6 @@ ServiceBase::ServiceBase(std::shared_ptr node_handle) node_logger_(rclcpp::get_node_logger(node_handle_.get())) {} -ServiceBase::~ServiceBase() -{ - clear_on_new_request_callback(); -} bool ServiceBase::take_type_erased_request(void * request_out, rmw_request_id_t & request_id_out) diff --git a/rclcpp/src/rclcpp/signal_handler.cpp b/rclcpp/src/rclcpp/signal_handler.cpp index 35ceb56781..7085c63bdf 100644 --- a/rclcpp/src/rclcpp/signal_handler.cpp +++ b/rclcpp/src/rclcpp/signal_handler.cpp @@ -191,7 +191,9 @@ SignalHandler::uninstall() signal_handlers_options_ = SignalHandlerOptions::None; RCLCPP_DEBUG(get_logger(), "SignalHandler::uninstall(): notifying deferred signal handler"); notify_signal_handler(); - signal_handler_thread_.join(); + if (signal_handler_thread_.joinable()) { + signal_handler_thread_.join(); + } teardown_wait_for_signal(); } catch (...) { installed_.exchange(true); diff --git a/rclcpp/src/rclcpp/subscription_base.cpp b/rclcpp/src/rclcpp/subscription_base.cpp index 300f465a41..0225747b3a 100644 --- a/rclcpp/src/rclcpp/subscription_base.cpp +++ b/rclcpp/src/rclcpp/subscription_base.cpp @@ -39,12 +39,15 @@ SubscriptionBase::SubscriptionBase( const rosidl_message_type_support_t & type_support_handle, const std::string & topic_name, const rcl_subscription_options_t & subscription_options, + const SubscriptionEventCallbacks & event_callbacks, + bool use_default_callbacks, bool is_serialized) : node_base_(node_base), node_handle_(node_base_->get_shared_rcl_node_handle()), node_logger_(rclcpp::get_node_logger(node_handle_.get())), use_intra_process_(false), intra_process_subscription_id_(0), + event_callbacks_(event_callbacks), type_support_(type_support_handle), is_serialized_(is_serialized) { @@ -80,20 +83,14 @@ SubscriptionBase::SubscriptionBase( rcl_node_get_name(rcl_node_handle), rcl_node_get_namespace(rcl_node_handle)); } - rclcpp::exceptions::throw_from_rcl_error(ret, "could not create subscription"); } + + bind_event_callbacks(event_callbacks_, use_default_callbacks); } SubscriptionBase::~SubscriptionBase() { - clear_on_new_message_callback(); - - for (const auto & pair : event_handlers_) { - rcl_subscription_event_type_t event_type = pair.first; - clear_on_new_qos_event_callback(event_type); - } - if (!use_intra_process_) { return; } @@ -108,6 +105,43 @@ SubscriptionBase::~SubscriptionBase() ipm->remove_subscription(intra_process_subscription_id_); } +void +SubscriptionBase::bind_event_callbacks( + const SubscriptionEventCallbacks & event_callbacks, bool use_default_callbacks) +{ + if (event_callbacks.deadline_callback) { + this->add_event_handler( + event_callbacks.deadline_callback, + RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED); + } + if (event_callbacks.liveliness_callback) { + this->add_event_handler( + event_callbacks.liveliness_callback, + RCL_SUBSCRIPTION_LIVELINESS_CHANGED); + } + if (event_callbacks.incompatible_qos_callback) { + this->add_event_handler( + event_callbacks.incompatible_qos_callback, + RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS); + } else if (use_default_callbacks) { + // Register default callback when not specified + try { + this->add_event_handler( + [this](QOSRequestedIncompatibleQoSInfo & info) { + this->default_incompatible_qos_callback(info); + }, + RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS); + } catch (UnsupportedEventTypeException & /*exc*/) { + // pass + } + } + if (event_callbacks.message_lost_callback) { + this->add_event_handler( + event_callbacks.message_lost_callback, + RCL_SUBSCRIPTION_MESSAGE_LOST); + } +} + const char * SubscriptionBase::get_topic_name() const { diff --git a/rclcpp/src/rclcpp/subscription_intra_process_base.cpp b/rclcpp/src/rclcpp/subscription_intra_process_base.cpp index 21ccb433ff..b13123b65b 100644 --- a/rclcpp/src/rclcpp/subscription_intra_process_base.cpp +++ b/rclcpp/src/rclcpp/subscription_intra_process_base.cpp @@ -17,11 +17,6 @@ using rclcpp::experimental::SubscriptionIntraProcessBase; -SubscriptionIntraProcessBase::~SubscriptionIntraProcessBase() -{ - clear_on_ready_callback(); -} - void SubscriptionIntraProcessBase::add_to_wait_set(rcl_wait_set_t * wait_set) { diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index 21c42530a6..83b0c986eb 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -91,10 +91,13 @@ class ClocksState final // Attach a clock void attachClock(rclcpp::Clock::SharedPtr clock) { - if (clock->get_clock_type() != RCL_ROS_TIME) { - throw std::invalid_argument("Cannot attach clock to a time source that's not a ROS clock"); + { + std::lock_guard clock_guard(clock->get_clock_mutex()); + if (clock->get_clock_type() != RCL_ROS_TIME && ros_time_active_) { + throw std::invalid_argument( + "ros_time_active_ can't be true while clock is not of RCL_ROS_TIME type"); + } } - std::lock_guard guard(clock_list_lock_); associated_clocks_.push_back(clock); // Set the clock to zero unless there's a recently received message @@ -125,27 +128,32 @@ class ClocksState final { std::lock_guard clock_guard(clock->get_clock_mutex()); - // Do change - if (!set_ros_time_enabled && clock->ros_time_is_active()) { - auto ret = rcl_disable_ros_time_override(clock->get_clock_handle()); - if (ret != RCL_RET_OK) { - rclcpp::exceptions::throw_from_rcl_error( - ret, "Failed to disable ros_time_override_status"); + if (clock->get_clock_type() == RCL_ROS_TIME) { + // Do change + if (!set_ros_time_enabled && clock->ros_time_is_active()) { + auto ret = rcl_disable_ros_time_override(clock->get_clock_handle()); + if (ret != RCL_RET_OK) { + rclcpp::exceptions::throw_from_rcl_error( + ret, "Failed to disable ros_time_override_status"); + } + } else if (set_ros_time_enabled && !clock->ros_time_is_active()) { + auto ret = rcl_enable_ros_time_override(clock->get_clock_handle()); + if (ret != RCL_RET_OK) { + rclcpp::exceptions::throw_from_rcl_error( + ret, "Failed to enable ros_time_override_status"); + } } - } else if (set_ros_time_enabled && !clock->ros_time_is_active()) { - auto ret = rcl_enable_ros_time_override(clock->get_clock_handle()); + + auto ret = rcl_set_ros_time_override( + clock->get_clock_handle(), + rclcpp::Time(*msg).nanoseconds()); if (ret != RCL_RET_OK) { rclcpp::exceptions::throw_from_rcl_error( - ret, "Failed to enable ros_time_override_status"); + ret, "Failed to set ros_time_override_status"); } - } - - auto ret = rcl_set_ros_time_override( - clock->get_clock_handle(), - rclcpp::Time(*msg).nanoseconds()); - if (ret != RCL_RET_OK) { - rclcpp::exceptions::throw_from_rcl_error( - ret, "Failed to set ros_time_override_status"); + } else if (set_ros_time_enabled) { + throw std::invalid_argument( + "set_ros_time_enabled can't be true while clock is not of RCL_ROS_TIME type"); } } @@ -166,6 +174,18 @@ class ClocksState final last_msg_set_ = msg; } + bool are_all_clocks_rcl_ros_time() + { + std::lock_guard guard(clock_list_lock_); + for (auto & clock : associated_clocks_) { + std::lock_guard clock_guard(clock->get_clock_mutex()); + if (clock->get_clock_type() != RCL_ROS_TIME) { + return false; + } + } + return true; + } + private: // Store (and update on node attach) logger for logging. Logger logger_; @@ -266,6 +286,10 @@ class TimeSource::NodeState final throw std::invalid_argument("Invalid type for parameter 'use_sim_time', should be 'bool'"); } + on_set_parameters_callback_ = node_parameters_->add_on_set_parameters_callback( + std::bind(&TimeSource::NodeState::on_set_parameters, this, std::placeholders::_1)); + + // TODO(tfoote) use parameters interface not subscribe to events via topic ticketed #609 parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event( node_topics_, @@ -285,6 +309,10 @@ class TimeSource::NodeState final // can't possibly call any of the callbacks as we are cleaning up. destroy_clock_sub(); clocks_state_.disable_ros_time(); + if (on_set_parameters_callback_) { + node_parameters_->remove_on_set_parameters_callback(on_set_parameters_callback_.get()); + } + on_set_parameters_callback_.reset(); parameter_subscription_.reset(); node_base_.reset(); node_topics_.reset(); @@ -419,10 +447,34 @@ class TimeSource::NodeState final clock_subscription_.reset(); } + // On set Parameters callback handle + node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_{nullptr}; + // Parameter Event subscription using ParamSubscriptionT = rclcpp::Subscription; std::shared_ptr parameter_subscription_; + // Callback for parameter settings + rcl_interfaces::msg::SetParametersResult on_set_parameters( + const std::vector & parameters) + { + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + for (const auto & param : parameters) { + if (param.get_name() == "use_sim_time" && param.get_type() == rclcpp::PARAMETER_BOOL) { + if (param.as_bool() && !(clocks_state_.are_all_clocks_rcl_ros_time())) { + result.successful = false; + result.reason = + "use_sim_time parameter can't be true while clocks are not all of RCL_ROS_TIME type"; + RCLCPP_ERROR( + logger_, + "use_sim_time parameter can't be true while clocks are not all of RCL_ROS_TIME type"); + } + } + } + return result; + } + // Callback for parameter updates void on_parameter_event(std::shared_ptr event) { diff --git a/rclcpp/test/rclcpp/CMakeLists.txt b/rclcpp/test/rclcpp/CMakeLists.txt index 6f915feef5..6dffb543e9 100644 --- a/rclcpp/test/rclcpp/CMakeLists.txt +++ b/rclcpp/test/rclcpp/CMakeLists.txt @@ -100,15 +100,20 @@ if(TARGET test_create_subscription) "test_msgs" ) endif() -ament_add_gtest(test_add_callback_groups_to_executor - test_add_callback_groups_to_executor.cpp - TIMEOUT 120) -if(TARGET test_add_callback_groups_to_executor) - target_link_libraries(test_add_callback_groups_to_executor ${PROJECT_NAME}) - ament_target_dependencies(test_add_callback_groups_to_executor - "test_msgs" +function(test_add_callback_groups_to_executor_for_rmw_implementation) + set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) + ament_add_gmock(test_add_callback_groups_to_executor${target_suffix} test_add_callback_groups_to_executor.cpp + ENV ${rmw_implementation_env_var} + TIMEOUT 120 ) -endif() + if(TARGET test_add_callback_groups_to_executor${target_suffix}) + target_link_libraries(test_add_callback_groups_to_executor${target_suffix} ${PROJECT_NAME}) + ament_target_dependencies(test_add_callback_groups_to_executor${target_suffix} + "test_msgs" + ) + endif() +endfunction() +call_for_each_rmw_implementation(test_add_callback_groups_to_executor_for_rmw_implementation) ament_add_gtest(test_expand_topic_or_service_name test_expand_topic_or_service_name.cpp) if(TARGET test_expand_topic_or_service_name) ament_target_dependencies(test_expand_topic_or_service_name @@ -229,6 +234,11 @@ if(TARGET test_node_interfaces__node_graph) "test_msgs") target_link_libraries(test_node_interfaces__node_graph ${PROJECT_NAME} mimick) endif() +ament_add_gtest(test_node_interfaces__node_interfaces + node_interfaces/test_node_interfaces.cpp) +if(TARGET test_node_interfaces__node_interfaces) + target_link_libraries(test_node_interfaces__node_interfaces ${PROJECT_NAME} mimick) +endif() ament_add_gtest(test_node_interfaces__node_parameters node_interfaces/test_node_parameters.cpp) if(TARGET test_node_interfaces__node_parameters) @@ -257,6 +267,11 @@ ament_add_gtest(test_node_interfaces__node_waitables if(TARGET test_node_interfaces__node_waitables) target_link_libraries(test_node_interfaces__node_waitables ${PROJECT_NAME} mimick) endif() +ament_add_gtest(test_node_interfaces__test_template_utils # Compile time test + node_interfaces/detail/test_template_utils.cpp) +if(TARGET test_node_interfaces__test_template_utils) + target_link_libraries(test_node_interfaces__test_template_utils ${PROJECT_NAME}) +endif() # TODO(wjwwood): reenable these build failure tests when I can get Jenkins to ignore their output # rclcpp_add_build_failure_test(build_failure__get_node_topics_interface_const_ref_rclcpp_node @@ -299,7 +314,7 @@ if(TARGET test_init_options) ament_target_dependencies(test_init_options "rcl") target_link_libraries(test_init_options ${PROJECT_NAME} mimick) endif() -ament_add_gtest(test_parameter_client test_parameter_client.cpp) +ament_add_gmock(test_parameter_client test_parameter_client.cpp) if(TARGET test_parameter_client) ament_target_dependencies(test_parameter_client "rcl_interfaces" diff --git a/rclcpp/test/rclcpp/allocator/test_allocator_common.cpp b/rclcpp/test/rclcpp/allocator/test_allocator_common.cpp index 341846a3eb..4619b7665d 100644 --- a/rclcpp/test/rclcpp/allocator/test_allocator_common.cpp +++ b/rclcpp/test/rclcpp/allocator/test_allocator_common.cpp @@ -51,6 +51,53 @@ TEST(TestAllocatorCommon, retyped_allocate) { EXPECT_NO_THROW(code2()); } +TEST(TestAllocatorCommon, retyped_zero_allocate_basic) { + std::allocator allocator; + void * untyped_allocator = &allocator; + void * allocated_mem = + rclcpp::allocator::retyped_zero_allocate>(20u, 1u, untyped_allocator); + ASSERT_TRUE(nullptr != allocated_mem); + + auto code = [&untyped_allocator, allocated_mem]() { + rclcpp::allocator::retyped_deallocate>( + allocated_mem, untyped_allocator); + }; + EXPECT_NO_THROW(code()); +} + +TEST(TestAllocatorCommon, retyped_zero_allocate) { + std::allocator allocator; + void * untyped_allocator = &allocator; + void * allocated_mem = + rclcpp::allocator::retyped_zero_allocate>(20u, 1u, untyped_allocator); + // The more natural check here is ASSERT_NE(nullptr, ptr), but clang static + // analysis throws a false-positive memory leak warning. Use ASSERT_TRUE instead. + ASSERT_TRUE(nullptr != allocated_mem); + + auto code = [&untyped_allocator, allocated_mem]() { + rclcpp::allocator::retyped_deallocate>( + allocated_mem, untyped_allocator); + }; + EXPECT_NO_THROW(code()); + + allocated_mem = allocator.allocate(1); + // The more natural check here is ASSERT_NE(nullptr, ptr), but clang static + // analysis throws a false-positive memory leak warning. Use ASSERT_TRUE instead. + ASSERT_TRUE(nullptr != allocated_mem); + void * reallocated_mem = + rclcpp::allocator::retyped_reallocate>( + allocated_mem, 2u, untyped_allocator); + // The more natural check here is ASSERT_NE(nullptr, ptr), but clang static + // analysis throws a false-positive memory leak warning. Use ASSERT_TRUE instead. + ASSERT_TRUE(nullptr != reallocated_mem); + + auto code2 = [&untyped_allocator, reallocated_mem]() { + rclcpp::allocator::retyped_deallocate>( + reallocated_mem, untyped_allocator); + }; + EXPECT_NO_THROW(code2()); +} + TEST(TestAllocatorCommon, get_rcl_allocator) { std::allocator allocator; auto rcl_allocator = rclcpp::allocator::get_rcl_allocator(allocator); diff --git a/rclcpp/test/rclcpp/node_interfaces/detail/test_template_utils.cpp b/rclcpp/test/rclcpp/node_interfaces/detail/test_template_utils.cpp new file mode 100644 index 0000000000..9ae715ebce --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/detail/test_template_utils.cpp @@ -0,0 +1,56 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "rclcpp/detail/template_contains.hpp" +#include "rclcpp/detail/template_unique.hpp" + + +TEST(NoOpTests, test_node_interfaces_template_utils) { +} // This is just to let gtest work + +namespace rclcpp +{ +namespace detail +{ + +// This tests template logic at compile time +namespace +{ + +struct test_template_unique +{ + static_assert(template_unique_v, "failed"); + static_assert(template_unique_v, "failed"); + static_assert(!template_unique_v, "failed"); + static_assert(!template_unique_v, "failed"); + static_assert(!template_unique_v, "failed"); +}; + + +struct test_template_contains +{ + static_assert(template_contains_v, "failed"); + static_assert(template_contains_v, "failed"); + static_assert(template_contains_v, "failed"); + static_assert(!template_contains_v, "failed"); + static_assert(!template_contains_v, "failed"); + static_assert(!template_contains_v, "failed"); +}; + +} // namespace + +} // namespace detail +} // namespace rclcpp diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_interfaces.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_interfaces.cpp new file mode 100644 index 0000000000..ebb91c4770 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_interfaces.cpp @@ -0,0 +1,245 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_interfaces.hpp" +#include "rclcpp/node_interfaces/node_base_interface.hpp" +#include "rclcpp/node_interfaces/node_graph_interface.hpp" + +class TestNodeInterfaces : public ::testing::Test +{ +protected: + static void SetUpTestCase() + { + rclcpp::init(0, nullptr); + } + + static void TearDownTestCase() + { + rclcpp::shutdown(); + } +}; + +/* + Testing NodeInterfaces construction from nodes. + */ +TEST_F(TestNodeInterfaces, node_interfaces_nominal) { + auto node = std::make_shared("my_node"); + + // Create a NodeInterfaces for base and graph using a rclcpp::Node. + { + using rclcpp::node_interfaces::NodeInterfaces; + using rclcpp::node_interfaces::NodeBaseInterface; + using rclcpp::node_interfaces::NodeGraphInterface; + auto node_interfaces = NodeInterfaces(*node); + } + + // Implicit conversion of rclcpp::Node into function that uses NodeInterfaces of base. + { + using rclcpp::node_interfaces::NodeInterfaces; + using rclcpp::node_interfaces::NodeBaseInterface; + auto some_func = [](NodeInterfaces ni) { + auto base_interface = ni.get(); + }; + + some_func(*node); + } + + // Implicit narrowing of NodeInterfaces into a new interface NodeInterfaces with fewer interfaces. + { + using rclcpp::node_interfaces::NodeInterfaces; + using rclcpp::node_interfaces::NodeBaseInterface; + using rclcpp::node_interfaces::NodeGraphInterface; + auto some_func = [](NodeInterfaces ni_with_one) { + auto base_interface = ni_with_one.get(); + }; + + NodeInterfaces ni_with_two(*node); + + some_func(ni_with_two); + } + + // Create a NodeInterfaces via aggregation of interfaces in constructor. + { + using rclcpp::node_interfaces::NodeInterfaces; + using rclcpp::node_interfaces::NodeBaseInterface; + using rclcpp::node_interfaces::NodeGraphInterface; + auto loose_node_base = node->get_node_base_interface(); + auto loose_node_graph = node->get_node_graph_interface(); + auto ni = NodeInterfaces( + loose_node_base, + loose_node_graph); + } +} + +/* + Test construction with all standard rclcpp::node_interfaces::Node*Interfaces. + */ +TEST_F(TestNodeInterfaces, node_interfaces_standard_interfaces) { + auto node = std::make_shared("my_node", "/ns"); + + auto ni = rclcpp::node_interfaces::NodeInterfaces< + rclcpp::node_interfaces::NodeBaseInterface, + rclcpp::node_interfaces::NodeClockInterface, + rclcpp::node_interfaces::NodeGraphInterface, + rclcpp::node_interfaces::NodeLoggingInterface, + rclcpp::node_interfaces::NodeTimersInterface, + rclcpp::node_interfaces::NodeTopicsInterface, + rclcpp::node_interfaces::NodeServicesInterface, + rclcpp::node_interfaces::NodeWaitablesInterface, + rclcpp::node_interfaces::NodeParametersInterface, + rclcpp::node_interfaces::NodeTimeSourceInterface + >(*node); +} + +/* + Testing getters. + */ +TEST_F(TestNodeInterfaces, ni_init) { + auto node = std::make_shared("my_node", "/ns"); + + using rclcpp::node_interfaces::NodeInterfaces; + using rclcpp::node_interfaces::NodeBaseInterface; + using rclcpp::node_interfaces::NodeClockInterface; + using rclcpp::node_interfaces::NodeGraphInterface; + using rclcpp::node_interfaces::NodeLoggingInterface; + using rclcpp::node_interfaces::NodeTimersInterface; + using rclcpp::node_interfaces::NodeTopicsInterface; + using rclcpp::node_interfaces::NodeServicesInterface; + using rclcpp::node_interfaces::NodeWaitablesInterface; + using rclcpp::node_interfaces::NodeParametersInterface; + using rclcpp::node_interfaces::NodeTimeSourceInterface; + + auto ni = NodeInterfaces< + NodeBaseInterface, + NodeClockInterface, + NodeGraphInterface, + NodeLoggingInterface, + NodeTimersInterface, + NodeTopicsInterface, + NodeServicesInterface, + NodeWaitablesInterface, + NodeParametersInterface, + NodeTimeSourceInterface + >(*node); + + { + auto base = ni.get(); + base = ni.get_node_base_interface(); + EXPECT_STREQ(base->get_name(), "my_node"); // Test for functionality + } + { + auto clock = ni.get(); + clock = ni.get_node_clock_interface(); + clock->get_clock(); + } + { + auto graph = ni.get(); + graph = ni.get_node_graph_interface(); + } + { + auto logging = ni.get(); + logging = ni.get_node_logging_interface(); + } + { + auto timers = ni.get(); + timers = ni.get_node_timers_interface(); + } + { + auto topics = ni.get(); + topics = ni.get_node_topics_interface(); + } + { + auto services = ni.get(); + services = ni.get_node_services_interface(); + } + { + auto waitables = ni.get(); + waitables = ni.get_node_waitables_interface(); + } + { + auto parameters = ni.get(); + parameters = ni.get_node_parameters_interface(); + } + { + auto time_source = ni.get(); + time_source = ni.get_node_time_source_interface(); + } +} + +/* + Testing macro'ed getters. + */ +TEST_F(TestNodeInterfaces, ni_all_init) { + auto node = std::make_shared("my_node", "/ns"); + + using rclcpp::node_interfaces::NodeInterfaces; + using rclcpp::node_interfaces::NodeBaseInterface; + using rclcpp::node_interfaces::NodeClockInterface; + using rclcpp::node_interfaces::NodeGraphInterface; + using rclcpp::node_interfaces::NodeLoggingInterface; + using rclcpp::node_interfaces::NodeTimersInterface; + using rclcpp::node_interfaces::NodeTopicsInterface; + using rclcpp::node_interfaces::NodeServicesInterface; + using rclcpp::node_interfaces::NodeWaitablesInterface; + using rclcpp::node_interfaces::NodeParametersInterface; + using rclcpp::node_interfaces::NodeTimeSourceInterface; + + auto ni = rclcpp::node_interfaces::NodeInterfaces(*node); + + { + auto base = ni.get(); + base = ni.get_node_base_interface(); + EXPECT_STREQ(base->get_name(), "my_node"); // Test for functionality + } + { + auto clock = ni.get(); + clock = ni.get_node_clock_interface(); + clock->get_clock(); + } + { + auto graph = ni.get(); + graph = ni.get_node_graph_interface(); + } + { + auto logging = ni.get(); + logging = ni.get_node_logging_interface(); + } + { + auto timers = ni.get(); + timers = ni.get_node_timers_interface(); + } + { + auto topics = ni.get(); + topics = ni.get_node_topics_interface(); + } + { + auto services = ni.get(); + services = ni.get_node_services_interface(); + } + { + auto waitables = ni.get(); + waitables = ni.get_node_waitables_interface(); + } + { + auto parameters = ni.get(); + parameters = ni.get_node_parameters_interface(); + } + { + auto time_source = ni.get(); + time_source = ni.get_node_time_source_interface(); + } +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp index 31b755b4a7..58bf010767 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp @@ -31,6 +31,8 @@ #include "../../mocking_utils/patch.hpp" #include "../../utils/rclcpp_gtest_macros.hpp" +#include "rcpputils/filesystem_helper.hpp" + class TestNodeParameters : public ::testing::Test { public: @@ -47,6 +49,7 @@ class TestNodeParameters : public ::testing::Test dynamic_cast( node->get_node_parameters_interface().get()); ASSERT_NE(nullptr, node_parameters); + test_resources_path /= "test_node_parameters"; } void TearDown() @@ -57,6 +60,8 @@ class TestNodeParameters : public ::testing::Test protected: std::shared_ptr node; rclcpp::node_interfaces::NodeParameters * node_parameters; + + rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY}; }; TEST_F(TestNodeParameters, construct_destruct_rcl_errors) { @@ -170,7 +175,7 @@ TEST_F(TestNodeParameters, set_parameters) { EXPECT_TRUE(result[0].successful); } -TEST_F(TestNodeParameters, add_remove_parameters_callback) { +TEST_F(TestNodeParameters, add_remove_on_set_parameters_callback) { rcl_interfaces::msg::ParameterDescriptor bool_descriptor; bool_descriptor.name = "bool_parameter"; bool_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; @@ -197,5 +202,248 @@ TEST_F(TestNodeParameters, add_remove_parameters_callback) { RCLCPP_EXPECT_THROW_EQ( node_parameters->remove_on_set_parameters_callback(handle.get()), - std::runtime_error("Callback doesn't exist")); + std::runtime_error("On set parameter callback doesn't exist")); +} + +TEST_F(TestNodeParameters, add_remove_pre_set_parameters_callback) { + // `add_pre_set_parameters_callback` used to modify parameters list. + auto modify_parameter_list_callback = [](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == "param1") { + parameters.emplace_back("param2", 2.0); + } + } + }; + + // `add_pre_set_parameters_callback` used to make the parameters list empty. + auto empty_parameter_list_callback = [](std::vector & parameters) { + parameters = {}; + }; + + auto handle1 = + node_parameters->add_pre_set_parameters_callback(modify_parameter_list_callback); + + double default_value = 0.0; + node_parameters->declare_parameter( + "param1", rclcpp::ParameterValue(default_value)); + node_parameters->declare_parameter( + "param2", rclcpp::ParameterValue(default_value)); + + // verify that `declare_parameter` does not call any of the callbacks registered with + // `add_pre_set_parameters_callback` + EXPECT_TRUE(node_parameters->has_parameter("param1")); + EXPECT_EQ(node_parameters->get_parameter("param1").get_value(), default_value); + EXPECT_TRUE(node_parameters->has_parameter("param2")); + EXPECT_EQ(node_parameters->get_parameter("param2").get_value(), default_value); + + // verify that the `param2` was set successfully conditioned on setting of + // `param1` + const std::vector parameters_to_be_set = { + rclcpp::Parameter("param1", 1.0)}; + auto result = node_parameters->set_parameters(parameters_to_be_set); + // we expect the result size to be same as the original "parameters_to_be_set" + // since the pre set parameter callback will set the modified param list atomically. + ASSERT_EQ(1u, result.size()); + EXPECT_TRUE(result[0].successful); + EXPECT_TRUE(node_parameters->has_parameter("param1")); + EXPECT_EQ(node_parameters->get_parameter("param1").get_value(), 1.0); + EXPECT_TRUE(node_parameters->has_parameter("param2")); + EXPECT_EQ(node_parameters->get_parameter("param2").get_value(), 2.0); + EXPECT_NO_THROW(node_parameters->remove_pre_set_parameters_callback(handle1.get())); + RCLCPP_EXPECT_THROW_EQ( + node_parameters->remove_pre_set_parameters_callback(handle1.get()), + std::runtime_error("Pre set parameter callback doesn't exist")); + + // verify that the result should be unsuccessful if the pre set callback makes + // parameter list empty + auto handle2 = + node_parameters->add_pre_set_parameters_callback(empty_parameter_list_callback); + auto results = node_parameters->set_parameters(parameters_to_be_set); + + std::string reason = "parameter list cannot be empty, this might be due to " + "pre_set_parameters_callback modifying the original parameters list."; + EXPECT_FALSE(results[0].successful); + EXPECT_EQ(results[0].reason, reason); + EXPECT_NO_THROW(node_parameters->remove_pre_set_parameters_callback(handle2.get())); + RCLCPP_EXPECT_THROW_EQ( + node_parameters->remove_pre_set_parameters_callback(handle2.get()), + std::runtime_error("Pre set parameter callback doesn't exist")); +} + +TEST_F(TestNodeParameters, add_remove_post_set_parameters_callback) { + rcl_interfaces::msg::ParameterDescriptor param1_descriptor; + param1_descriptor.name = "double_parameter1"; + param1_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + param1_descriptor.read_only = false; + + rcl_interfaces::msg::ParameterDescriptor param2_descriptor; + param2_descriptor.name = "double_parameter2"; + param2_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + param2_descriptor.read_only = false; + + double variable_tracking_param1_internally = node_parameters->declare_parameter( + "param1", rclcpp::ParameterValue(0.0), param1_descriptor, false).get(); + double variable_tracking_param2_internally = node_parameters->declare_parameter( + "param2", rclcpp::ParameterValue(0.0), param2_descriptor, false).get(); + + EXPECT_EQ(variable_tracking_param1_internally, 0.0); + EXPECT_EQ(variable_tracking_param2_internally, 0.0); + + const std::vector parameters_to_be_set = { + rclcpp::Parameter("param1", 1.0), + rclcpp::Parameter("param2", 2.0)}; + + // register a callback for successful set parameter and change the internally tracked variables. + auto callback = [&](const std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == "param1") { + variable_tracking_param1_internally = param.get_value(); + } else if (param.get_name() == "param2") { + variable_tracking_param2_internally = param.get_value(); + } + } + }; + + auto handle = node_parameters->add_post_set_parameters_callback(callback); + auto result = node_parameters->set_parameters(parameters_to_be_set); + ASSERT_EQ(2u, result.size()); + EXPECT_TRUE(result[0].successful); + EXPECT_TRUE(result[1].successful); + EXPECT_TRUE(node_parameters->has_parameter("param1")); + EXPECT_TRUE(node_parameters->has_parameter("param2")); + EXPECT_EQ(variable_tracking_param1_internally, 1.0); + EXPECT_EQ(variable_tracking_param2_internally, 2.0); + + EXPECT_NO_THROW(node_parameters->remove_post_set_parameters_callback(handle.get())); + + RCLCPP_EXPECT_THROW_EQ( + node_parameters->remove_post_set_parameters_callback(handle.get()), + std::runtime_error("Post set parameter callback doesn't exist")); +} + +TEST_F(TestNodeParameters, wildcard_with_namespace) +{ + rclcpp::NodeOptions opts; + opts.arguments( + { + "--ros-args", + "--params-file", (test_resources_path / "wildcards.yaml").string() + }); + + std::shared_ptr node = std::make_shared("node2", "ns", opts); + + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + const auto & parameter_overrides = node_parameters->get_parameter_overrides(); + EXPECT_EQ(7u, parameter_overrides.size()); + EXPECT_EQ(parameter_overrides.at("full_wild").get(), "full_wild"); + EXPECT_EQ(parameter_overrides.at("namespace_wild").get(), "namespace_wild"); + EXPECT_EQ( + parameter_overrides.at("namespace_wild_another").get(), + "namespace_wild_another"); + EXPECT_EQ( + parameter_overrides.at("namespace_wild_one_star").get(), + "namespace_wild_one_star"); + EXPECT_EQ(parameter_overrides.at("node_wild_in_ns").get(), "node_wild_in_ns"); + EXPECT_EQ( + parameter_overrides.at("node_wild_in_ns_another").get(), + "node_wild_in_ns_another"); + EXPECT_EQ(parameter_overrides.at("explicit_in_ns").get(), "explicit_in_ns"); + EXPECT_EQ(parameter_overrides.count("should_not_appear"), 0u); +} + +TEST_F(TestNodeParameters, wildcard_no_namespace) +{ + rclcpp::NodeOptions opts; + opts.arguments( + { + "--ros-args", + "--params-file", (test_resources_path / "wildcards.yaml").string() + }); + + std::shared_ptr node = std::make_shared("node2", opts); + + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + const auto & parameter_overrides = node_parameters->get_parameter_overrides(); + EXPECT_EQ(5u, parameter_overrides.size()); + EXPECT_EQ(parameter_overrides.at("full_wild").get(), "full_wild"); + EXPECT_EQ(parameter_overrides.at("namespace_wild").get(), "namespace_wild"); + EXPECT_EQ( + parameter_overrides.at("namespace_wild_another").get(), + "namespace_wild_another"); + EXPECT_EQ(parameter_overrides.at("node_wild_no_ns").get(), "node_wild_no_ns"); + EXPECT_EQ(parameter_overrides.at("explicit_no_ns").get(), "explicit_no_ns"); + EXPECT_EQ(parameter_overrides.count("should_not_appear"), 0u); + // "/*" match exactly one token, not expect to get `namespace_wild_one_star` + EXPECT_EQ(parameter_overrides.count("namespace_wild_one_star"), 0u); +} + +TEST_F(TestNodeParameters, params_by_order) +{ + rclcpp::NodeOptions opts; + opts.arguments( + { + "--ros-args", + "--params-file", (test_resources_path / "params_by_order.yaml").string() + }); + + std::shared_ptr node = std::make_shared("node2", "ns", opts); + + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + const auto & parameter_overrides = node_parameters->get_parameter_overrides(); + EXPECT_EQ(3u, parameter_overrides.size()); + EXPECT_EQ(parameter_overrides.at("a_value").get(), "last_one_win"); + EXPECT_EQ(parameter_overrides.at("foo").get(), "foo"); + EXPECT_EQ(parameter_overrides.at("bar").get(), "bar"); +} + +TEST_F(TestNodeParameters, complicated_wildcards) +{ + rclcpp::NodeOptions opts; + opts.arguments( + { + "--ros-args", + "--params-file", (test_resources_path / "complicated_wildcards.yaml").string() + }); + + { + // regex matched: /**/foo/*/bar + std::shared_ptr node = + std::make_shared("node2", "/a/b/c/foo/d/bar", opts); + + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + const auto & parameter_overrides = node_parameters->get_parameter_overrides(); + EXPECT_EQ(2u, parameter_overrides.size()); + EXPECT_EQ(parameter_overrides.at("foo").get(), "foo"); + EXPECT_EQ(parameter_overrides.at("bar").get(), "bar"); + } + + { + // regex not matched: /**/foo/*/bar + std::shared_ptr node = + std::make_shared("node2", "/a/b/c/foo/bar", opts); + + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + const auto & parameter_overrides = node_parameters->get_parameter_overrides(); + EXPECT_EQ(0u, parameter_overrides.size()); + } } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp index a99633bec6..ecfc89a6aa 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp @@ -36,16 +36,14 @@ const rosidl_message_type_support_t EmptyTypeSupport() return *rosidl_typesupport_cpp::get_message_type_support_handle(); } -const rcl_publisher_options_t PublisherOptions() +const rclcpp::PublisherOptionsWithAllocator> PublisherOptions() { - return rclcpp::PublisherOptionsWithAllocator>().template - to_rcl_publisher_options(rclcpp::QoS(10)); + return rclcpp::PublisherOptionsWithAllocator>(); } -const rcl_subscription_options_t SubscriptionOptions() +const rclcpp::SubscriptionOptionsWithAllocator> SubscriptionOptions() { - return rclcpp::SubscriptionOptionsWithAllocator>().template - to_rcl_subscription_options(rclcpp::QoS(10)); + return rclcpp::SubscriptionOptionsWithAllocator>(); } } // namespace @@ -55,7 +53,9 @@ class TestPublisher : public rclcpp::PublisherBase public: explicit TestPublisher(rclcpp::Node * node) : rclcpp::PublisherBase( - node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), PublisherOptions()) {} + node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), + PublisherOptions().to_rcl_publisher_options(rclcpp::QoS(10)), + PublisherOptions().event_callbacks, PublisherOptions().use_default_callbacks) {} }; class TestSubscription : public rclcpp::SubscriptionBase @@ -63,7 +63,9 @@ class TestSubscription : public rclcpp::SubscriptionBase public: explicit TestSubscription(rclcpp::Node * node) : rclcpp::SubscriptionBase( - node->get_node_base_interface().get(), EmptyTypeSupport(), "topic", SubscriptionOptions()) {} + node->get_node_base_interface().get(), EmptyTypeSupport(), "topic", + SubscriptionOptions().to_rcl_subscription_options(rclcpp::QoS(10)), + SubscriptionOptions().event_callbacks, SubscriptionOptions().use_default_callbacks) {} std::shared_ptr create_message() override {return nullptr;} std::shared_ptr diff --git a/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp b/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp index e1b916e9c0..1779d5d88e 100644 --- a/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp +++ b/rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp @@ -162,7 +162,7 @@ class TestAllocatorMemoryStrategy : public ::testing::Test services_.push_back( node_with_service->create_service( - "service", std::move(service_callback), rmw_qos_profile_services_default, callback_group)); + "service", std::move(service_callback), rclcpp::ServicesQoS(), callback_group)); return node_with_service; } @@ -177,7 +177,7 @@ class TestAllocatorMemoryStrategy : public ::testing::Test clients_.push_back( node_with_client->create_client( - "service", rmw_qos_profile_services_default, callback_group)); + "service", rclcpp::ServicesQoS(), callback_group)); return node_with_client; } @@ -793,7 +793,7 @@ TEST_F(TestAllocatorMemoryStrategy, get_next_service_out_of_scope) { [](const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {}; auto service = node->create_service( - "service", std::move(service_callback), rmw_qos_profile_services_default, callback_group); + "service", std::move(service_callback), rclcpp::ServicesQoS(), callback_group); node->for_each_callback_group( [node, &weak_groups_to_nodes](rclcpp::CallbackGroup::SharedPtr group_ptr) @@ -831,7 +831,7 @@ TEST_F(TestAllocatorMemoryStrategy, get_next_client_out_of_scope) { node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); auto client = node->create_client( - "service", rmw_qos_profile_services_default, callback_group); + "service", rclcpp::ServicesQoS(), callback_group); weak_groups_to_nodes.insert( std::pair("my_node", "/ns"); + + // create a thread running an executor with a new callback group for a coming subscriber + rclcpp::CallbackGroup::SharedPtr cb_grp = node->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, false); + rclcpp::executors::SingleThreadedExecutor cb_grp_executor; + + std::promise received_message_promise; + auto received_message_future = received_message_promise.get_future(); + rclcpp::FutureReturnCode return_code = rclcpp::FutureReturnCode::TIMEOUT; + std::thread cb_grp_thread = std::thread( + [&cb_grp, &node, &cb_grp_executor, &received_message_future, &return_code]() { + cb_grp_executor.add_callback_group(cb_grp, node->get_node_base_interface()); + return_code = cb_grp_executor.spin_until_future_complete(received_message_future, 10s); + }); + + // expect the subscriber to receive a message + auto sub_callback = [&received_message_promise](test_msgs::msg::Empty::ConstSharedPtr) { + received_message_promise.set_value(true); + }; + + rclcpp::Subscription::SharedPtr subscription; + rclcpp::Publisher::SharedPtr publisher; + // to create a timer with a callback run on another executor + rclcpp::TimerBase::SharedPtr timer = nullptr; + std::promise timer_promise; + auto timer_callback = + [&subscription, &publisher, &timer, &cb_grp, &node, &sub_callback, &timer_promise]() { + if (timer) { + timer.reset(); + } + + // create a subscription using the `cb_grp` callback group + rclcpp::QoS qos = rclcpp::QoS(1).reliable(); + auto options = rclcpp::SubscriptionOptions(); + options.callback_group = cb_grp; + subscription = + node->create_subscription("topic_name", qos, sub_callback, options); + // create a publisher to send data + publisher = + node->create_publisher("topic_name", qos); + publisher->publish(test_msgs::msg::Empty()); + timer_promise.set_value(); + }; + + rclcpp::executors::SingleThreadedExecutor timer_executor; + timer = node->create_wall_timer(100ms, timer_callback); + timer_executor.add_node(node); + auto future = timer_promise.get_future(); + timer_executor.spin_until_future_complete(future); + cb_grp_thread.join(); + + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); + EXPECT_TRUE(received_message_future.get()); +} + /* * Test removing callback group from executor that its not associated with. */ diff --git a/rclcpp/test/rclcpp/test_client.cpp b/rclcpp/test/rclcpp/test_client.cpp index 7cb9b0af65..9070e1caa9 100644 --- a/rclcpp/test/rclcpp/test_client.cpp +++ b/rclcpp/test/rclcpp/test_client.cpp @@ -92,6 +92,30 @@ TEST_F(TestClient, construction_and_destruction) { { auto client = node->create_client("service"); } + { + // suppress deprecated function warning + #if !defined(_WIN32) + # pragma GCC diagnostic push + # pragma GCC diagnostic ignored "-Wdeprecated-declarations" + #else // !defined(_WIN32) + # pragma warning(push) + # pragma warning(disable: 4996) + #endif + + auto client = node->create_client( + "service", rmw_qos_profile_services_default); + + // remove warning suppression + #if !defined(_WIN32) + # pragma GCC diagnostic pop + #else // !defined(_WIN32) + # pragma warning(pop) + #endif + } + { + auto client = node->create_client( + "service", rclcpp::ServicesQoS()); + } { ASSERT_THROW( @@ -123,6 +147,27 @@ TEST_F(TestClient, construction_with_free_function) { nullptr); }, rclcpp::exceptions::InvalidServiceNameError); } + { + auto client = rclcpp::create_client( + node->get_node_base_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + "service", + rclcpp::ServicesQoS(), + nullptr); + } + { + ASSERT_THROW( + { + auto client = rclcpp::create_client( + node->get_node_base_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + "invalid_?service", + rclcpp::ServicesQoS(), + nullptr); + }, rclcpp::exceptions::InvalidServiceNameError); + } } TEST_F(TestClient, construct_with_rcl_error) { @@ -282,6 +327,27 @@ TEST_F(TestClientWithServer, test_client_remove_pending_request) { EXPECT_TRUE(client->remove_pending_request(future)); } +TEST_F(TestClientWithServer, prune_requests_older_than_no_pruned) { + auto client = node->create_client(service_name); + auto request = std::make_shared(); + auto future = client->async_send_request(request); + auto time = std::chrono::system_clock::now() + 1s; + + EXPECT_EQ(1u, client->prune_requests_older_than(time)); +} + +TEST_F(TestClientWithServer, prune_requests_older_than_with_pruned) { + auto client = node->create_client(service_name); + auto request = std::make_shared(); + auto future = client->async_send_request(request); + auto time = std::chrono::system_clock::now() + 1s; + + std::vector pruned_requests; + EXPECT_EQ(1u, client->prune_requests_older_than(time, &pruned_requests)); + ASSERT_EQ(1u, pruned_requests.size()); + EXPECT_EQ(future.request_id, pruned_requests[0]); +} + TEST_F(TestClientWithServer, async_send_request_rcl_send_request_error) { // Checking rcl_send_request in rclcpp::Client::async_send_request() auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_send_request, RCL_RET_ERROR); @@ -351,8 +417,8 @@ TEST_F(TestClient, on_new_response_callback) { auto client_node = std::make_shared("client_node", "ns"); auto server_node = std::make_shared("server_node", "ns"); - rmw_qos_profile_t client_qos = rmw_qos_profile_services_default; - client_qos.depth = 3; + rclcpp::ServicesQoS client_qos; + client_qos.keep_last(3); auto client = client_node->create_client("test_service", client_qos); std::atomic server_requests_count {0}; auto server_callback = [&server_requests_count]( @@ -455,32 +521,30 @@ TEST_F(TestClient, rcl_client_response_subscription_get_actual_qos_error) { } TEST_F(TestClient, client_qos) { - rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default; - qos_profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC; - uint64_t duration = 1; - qos_profile.deadline = {duration, duration}; - qos_profile.lifespan = {duration, duration}; - qos_profile.liveliness_lease_duration = {duration, duration}; + rclcpp::ServicesQoS qos_profile; + qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic); + rclcpp::Duration duration(std::chrono::nanoseconds(1)); + qos_profile.deadline(duration); + qos_profile.lifespan(duration); + qos_profile.liveliness_lease_duration(duration); auto client = node->create_client("client", qos_profile); - auto init_qos = - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile), qos_profile); auto rp_qos = client->get_request_publisher_actual_qos(); auto rs_qos = client->get_response_subscription_actual_qos(); - EXPECT_EQ(init_qos, rp_qos); + EXPECT_EQ(qos_profile, rp_qos); // Lifespan has no meaning for subscription/readers - rs_qos.lifespan(qos_profile.lifespan); - EXPECT_EQ(init_qos, rs_qos); + rs_qos.lifespan(qos_profile.lifespan()); + EXPECT_EQ(qos_profile, rs_qos); } TEST_F(TestClient, client_qos_depth) { using namespace std::literals::chrono_literals; - rmw_qos_profile_t client_qos_profile = rmw_qos_profile_default; - client_qos_profile.depth = 2; + rclcpp::ServicesQoS client_qos_profile; + client_qos_profile.keep_last(2); auto client = node->create_client("test_qos_depth", client_qos_profile); @@ -491,10 +555,10 @@ TEST_F(TestClient, client_qos_depth) { auto server_node = std::make_shared("server_node", "/ns"); - rmw_qos_profile_t server_qos_profile = rmw_qos_profile_default; + rclcpp::QoS server_qos(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); auto server = server_node->create_service( - "test_qos_depth", std::move(server_callback), server_qos_profile); + "test_qos_depth", std::move(server_callback), server_qos); auto request = std::make_shared(); ::testing::AssertionResult request_result = ::testing::AssertionSuccess(); @@ -522,10 +586,10 @@ TEST_F(TestClient, client_qos_depth) { std::this_thread::sleep_for(2ms); } - EXPECT_GT(server_cb_count_, client_qos_profile.depth); + EXPECT_GT(server_cb_count_, client_qos_profile.depth()); start = std::chrono::steady_clock::now(); - while ((client_cb_count_ < client_qos_profile.depth) && + while ((client_cb_count_ < client_qos_profile.depth()) && (std::chrono::steady_clock::now() - start) < 1s) { rclcpp::spin_some(node); @@ -535,5 +599,5 @@ TEST_F(TestClient, client_qos_depth) { // so more client callbacks might be called than expected. rclcpp::spin_some(node); - EXPECT_EQ(client_cb_count_, client_qos_profile.depth); + EXPECT_EQ(client_cb_count_, client_qos_profile.depth()); } diff --git a/rclcpp/test/rclcpp/test_create_timer.cpp b/rclcpp/test/rclcpp/test_create_timer.cpp index 13c3564544..f253af4838 100644 --- a/rclcpp/test/rclcpp/test_create_timer.cpp +++ b/rclcpp/test/rclcpp/test_create_timer.cpp @@ -62,7 +62,7 @@ TEST(TestCreateTimer, call_with_node_wrapper_compiles) rclcpp::shutdown(); } -TEST(TestCreateTimer, call_wall_timer_with_bad_arguments) +TEST(TestCreateWallTimer, call_wall_timer_with_bad_arguments) { rclcpp::init(0, nullptr); NodeWrapper node("test_create_wall_timers_with_bad_arguments"); @@ -117,6 +117,66 @@ TEST(TestCreateTimer, call_wall_timer_with_bad_arguments) rclcpp::shutdown(); } +TEST(TestCreateTimer, call_timer_with_bad_arguments) +{ + rclcpp::init(0, nullptr); + NodeWrapper node("test_create_timers_with_bad_arguments"); + auto callback = []() {}; + rclcpp::CallbackGroup::SharedPtr group = nullptr; + auto node_interface = + rclcpp::node_interfaces::get_node_base_interface(node).get(); + auto timers_interface = + rclcpp::node_interfaces::get_node_timers_interface(node).get(); + + auto clock = node.get_node_clock_interface()->get_clock(); + + // Negative period + EXPECT_THROW( + rclcpp::create_timer( + clock, -1ms, callback, group, node_interface, timers_interface), + std::invalid_argument); + + // Very negative period + constexpr auto nanoseconds_min = std::chrono::nanoseconds::min(); + EXPECT_THROW( + rclcpp::create_timer( + clock, nanoseconds_min, callback, group, node_interface, timers_interface), + std::invalid_argument); + + // Period must be less than nanoseconds::max() + constexpr auto nanoseconds_max = std::chrono::nanoseconds::min(); + EXPECT_THROW( + rclcpp::create_timer( + clock, nanoseconds_max, callback, group, node_interface, timers_interface), + std::invalid_argument); + + EXPECT_NO_THROW( + rclcpp::create_timer( + clock, nanoseconds_max - 1us, callback, group, node_interface, timers_interface)); + + EXPECT_NO_THROW( + rclcpp::create_timer(clock, 0ms, callback, group, node_interface, timers_interface)); + + // Period must be less than nanoseconds::max() + constexpr auto hours_max = std::chrono::hours::max(); + EXPECT_THROW( + rclcpp::create_timer( + clock, hours_max, callback, group, node_interface, timers_interface), + std::invalid_argument); + + // node_interface is null + EXPECT_THROW( + rclcpp::create_timer(clock, 1ms, callback, group, nullptr, timers_interface), + std::invalid_argument); + + // timers_interface is null + EXPECT_THROW( + rclcpp::create_timer(clock, 1ms, callback, group, node_interface, nullptr), + std::invalid_argument); + + rclcpp::shutdown(); +} + static void test_timer_callback(void) {} TEST(TestCreateTimer, timer_function_pointer) diff --git a/rclcpp/test/rclcpp/test_duration.cpp b/rclcpp/test/rclcpp/test_duration.cpp index 319ce06601..d5908c7d4b 100644 --- a/rclcpp/test/rclcpp/test_duration.cpp +++ b/rclcpp/test/rclcpp/test_duration.cpp @@ -52,9 +52,23 @@ TEST_F(TestDuration, operators) { EXPECT_EQ(sub.nanoseconds(), young.nanoseconds() - old.nanoseconds()); EXPECT_EQ(sub, young - old); + rclcpp::Duration addequal = old; + addequal += young; + EXPECT_EQ(addequal.nanoseconds(), old.nanoseconds() + young.nanoseconds()); + EXPECT_EQ(addequal, old + young); + + rclcpp::Duration subequal = young; + subequal -= old; + EXPECT_EQ(subequal.nanoseconds(), young.nanoseconds() - old.nanoseconds()); + EXPECT_EQ(subequal, young - old); + rclcpp::Duration scale = old * 3; EXPECT_EQ(scale.nanoseconds(), old.nanoseconds() * 3); + rclcpp::Duration scaleequal = old; + scaleequal *= 3; + EXPECT_EQ(scaleequal.nanoseconds(), old.nanoseconds() * 3); + rclcpp::Duration time = rclcpp::Duration(0, 0); rclcpp::Duration copy_constructor_duration(time); rclcpp::Duration assignment_op_duration = rclcpp::Duration(1, 0); diff --git a/rclcpp/test/rclcpp/test_memory_strategy.cpp b/rclcpp/test/rclcpp/test_memory_strategy.cpp index b6fff57a92..e96729a2a1 100644 --- a/rclcpp/test/rclcpp/test_memory_strategy.cpp +++ b/rclcpp/test/rclcpp/test_memory_strategy.cpp @@ -155,7 +155,7 @@ TEST_F(TestMemoryStrategy, get_service_by_handle) { { auto service = node->create_service( "service", std::move(service_callback), - rmw_qos_profile_services_default, callback_group); + rclcpp::ServicesQoS(), callback_group); service_handle = service->get_service_handle(); @@ -197,7 +197,7 @@ TEST_F(TestMemoryStrategy, get_client_by_handle) { node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); { auto client = node->create_client( - "service", rmw_qos_profile_services_default, callback_group); + "service", rclcpp::ServicesQoS(), callback_group); client_handle = client->get_client_handle(); weak_groups_to_nodes.insert( @@ -396,7 +396,7 @@ TEST_F(TestMemoryStrategy, get_group_by_service) { service = node->create_service( "service", std::move(service_callback), - rmw_qos_profile_services_default, callback_group); + rclcpp::ServicesQoS(), callback_group); weak_groups_to_nodes.insert( std::pair( @@ -435,7 +435,7 @@ TEST_F(TestMemoryStrategy, get_group_by_client) { node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); client = node->create_client( - "service", rmw_qos_profile_services_default, callback_group); + "service", rclcpp::ServicesQoS(), callback_group); weak_groups_to_nodes.insert( std::pair( diff --git a/rclcpp/test/rclcpp/test_node.cpp b/rclcpp/test/rclcpp/test_node.cpp index 58af342561..512c2c1384 100644 --- a/rclcpp/test/rclcpp/test_node.cpp +++ b/rclcpp/test/rclcpp/test_node.cpp @@ -95,6 +95,74 @@ TEST_F(TestNode, construction_and_destruction) { (void)node; }, rclcpp::exceptions::InvalidNamespaceError); } + + { + rclcpp::NodeOptions options; + ASSERT_NO_THROW( + { + const auto node = std::make_shared("my_node", "/ns", options); + EXPECT_EQ(RCL_ROS_TIME, node->get_clock()->get_clock_type()); + }); + } + + { + rclcpp::NodeOptions options; + options.parameter_overrides( + { + {"use_sim_time", true}, + }); + ASSERT_NO_THROW( + { + const auto node = std::make_shared("my_node", "/ns", options); + EXPECT_EQ(RCL_ROS_TIME, node->get_clock()->get_clock_type()); + }); + } + + { + rclcpp::NodeOptions options; + options.clock_type(RCL_SYSTEM_TIME); + ASSERT_NO_THROW( + { + const auto node = std::make_shared("my_node", "/ns", options); + EXPECT_EQ(RCL_SYSTEM_TIME, node->get_clock()->get_clock_type()); + }); + } + + { + rclcpp::NodeOptions options; + options.parameter_overrides( + { + {"use_sim_time", true}, + }); + options.clock_type(RCL_SYSTEM_TIME); + ASSERT_THROW( + const auto node = std::make_shared( + "my_node", "/ns", + options), std::invalid_argument); + } + + { + rclcpp::NodeOptions options; + options.clock_type(RCL_STEADY_TIME); + ASSERT_NO_THROW( + { + const auto node = std::make_shared("my_node", "/ns", options); + EXPECT_EQ(RCL_STEADY_TIME, node->get_clock()->get_clock_type()); + }); + } + + { + rclcpp::NodeOptions options; + options.parameter_overrides( + { + {"use_sim_time", true}, + }); + options.clock_type(RCL_STEADY_TIME); + ASSERT_THROW( + const auto node = std::make_shared( + "my_node", "/ns", + options), std::invalid_argument); + } } /* @@ -1444,6 +1512,36 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) { EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_STRING); EXPECT_EQ(value.get_value(), "asd"); } + { + // adding a parameter in "pre set parameter" callback, when that + // parameter has not been declared before will throw + auto name1 = "parameter"_unq; + auto name2 = "parameter"_unq; + auto default_value = 0; // default value of name1 param + + // declare name1 parameter only + node->declare_parameter(name1, default_value); + + // add undeclared parameter with name2 to modified list of parameters + auto pre_set_parameters = + [&](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == name1) { + parameters.emplace_back(rclcpp::Parameter(name2, 2)); + } + } + }; + + auto handler = node->add_pre_set_parameters_callback(pre_set_parameters); + EXPECT_THROW( + node->set_parameter(rclcpp::Parameter(name1, 4)), + rclcpp::exceptions::ParameterNotDeclaredException); + EXPECT_TRUE(node->has_parameter(name1)); + EXPECT_EQ(node->get_parameter(name1).get_value(), default_value); + EXPECT_FALSE(node->has_parameter(name2)); + RCPPUTILS_SCOPE_EXIT( + {node->remove_pre_set_parameters_callback(handler.get());}); // always reset + } } TEST_F(TestNode, set_parameter_undeclared_parameters_allowed) { @@ -1481,6 +1579,36 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_allowed) { EXPECT_TRUE(node->has_parameter(name)); EXPECT_EQ(node->get_parameter(name).get_value(), 43); } + { + // adding a parameter in "pre set parameter" callback, when that + // parameter has not been declared will not throw if undeclared + // parameters are allowed + auto name1 = "parameter"_unq; + auto name2 = "parameter"_unq; + + // declare name1 parameter only + node->declare_parameter(name1, 0); + + // add undeclared parameter with name2 to modified list of parameters + auto pre_set_parameters = + [&](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == name1) { + parameters.emplace_back(rclcpp::Parameter(name2, 2)); + } + } + }; + + auto handler = node->add_pre_set_parameters_callback(pre_set_parameters); + auto result = node->set_parameter(rclcpp::Parameter(name1, 1)); + EXPECT_TRUE(result.successful); + EXPECT_TRUE(node->has_parameter(name1)); + EXPECT_TRUE(node->has_parameter(name2)); + EXPECT_EQ(node->get_parameter(name1).get_value(), 1); + EXPECT_EQ(node->get_parameter(name2).get_value(), 2); + RCPPUTILS_SCOPE_EXIT( + {node->remove_pre_set_parameters_callback(handler.get());}); // always reset + } } TEST_F(TestNode, set_parameters_undeclared_parameters_not_allowed) { @@ -1625,6 +1753,51 @@ TEST_F(TestNode, set_parameters_undeclared_parameters_not_allowed) { EXPECT_FALSE(node->has_parameter(name)); } + { + // adding a parameter in "pre set parameter" callback when that + // parameter has not been declared before will throw. However, when + // multiple params are being set using "set_parameters", the params + // which are not conditioned on each other in "pre set callback" will + // still be set successfully. This is the desired behaviour since + // "set_parameters" sets params non atomically. + auto name1 = "parameter"_unq; + auto name2 = "parameter"_unq; + auto name3 = "parameter"_unq; + auto default_value = 0; + + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rclcpp::PARAMETER_INTEGER; + + // declare name1 and name2 parameter only + node->declare_parameter(name1, default_value, descriptor); + node->declare_parameter(name2, default_value, descriptor); + + // add undeclared parameter with name3 to modified list of parameters + // conditioned of name2 param + auto pre_set_parameters = + [&](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == name2) { + parameters.emplace_back(rclcpp::Parameter(name3, 3)); + } + } + }; + + auto handler = node->add_pre_set_parameters_callback(pre_set_parameters); + EXPECT_THROW( + node->set_parameters({rclcpp::Parameter(name1, 1), rclcpp::Parameter(name2, 2)}), + rclcpp::exceptions::ParameterNotDeclaredException); + EXPECT_TRUE(node->has_parameter(name1)); + EXPECT_TRUE(node->has_parameter(name2)); + EXPECT_FALSE(node->has_parameter(name3)); + + // we still expect the value of name1 param to be set successfully, since + // the setting of name2 param is only conditioned on setting of name3 param + EXPECT_EQ(node->get_parameter(name1).get_value(), 1); + EXPECT_EQ(node->get_parameter(name2).get_value(), default_value); + RCPPUTILS_SCOPE_EXIT( + {node->remove_pre_set_parameters_callback(handler.get());}); // always reset + } } // test set_parameters with undeclared allowed @@ -1673,6 +1846,48 @@ TEST_F(TestNode, set_parameters_undeclared_parameters_allowed) { EXPECT_EQ(node->get_parameter(name1).get_value(), 42); EXPECT_EQ(node->get_parameter(name2).get_value(), "test"); } + { + // adding a parameter in "pre set parameter" callback when that + // parameter has not been declared before will not throw when + // undeclared parameters are allowed. + auto name1 = "parameter"_unq; + auto name2 = "parameter"_unq; + auto name3 = "parameter"_unq; + auto default_value = 0; + + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rclcpp::PARAMETER_INTEGER; + + // declare name1 and name2 parameter only + node->declare_parameter(name1, default_value, descriptor); + node->declare_parameter(name2, default_value, descriptor); + + // add undeclared parameter with name3 to modified list of parameters + // conditioned of name2 param + auto pre_set_parameters = + [&](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == name2) { + parameters.emplace_back(rclcpp::Parameter(name3, 3)); + } + } + }; + + auto handler = node->add_pre_set_parameters_callback(pre_set_parameters); + auto results = node->set_parameters({rclcpp::Parameter(name1, 1), rclcpp::Parameter(name2, 2)}); + EXPECT_EQ(2u, results.size()); + EXPECT_TRUE(results[0].successful); + EXPECT_TRUE(results[1].successful); + EXPECT_TRUE(node->has_parameter(name1)); + EXPECT_TRUE(node->has_parameter(name2)); + EXPECT_TRUE(node->has_parameter(name3)); + EXPECT_EQ(node->get_parameter(name1).get_value(), 1); + EXPECT_EQ(node->get_parameter(name2).get_value(), 2); + EXPECT_EQ(node->get_parameter(name3).get_value(), 3); + + RCPPUTILS_SCOPE_EXIT( + {node->remove_pre_set_parameters_callback(handler.get());}); // always reset + } } TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_not_allowed) { @@ -1815,6 +2030,48 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_not_allowed) { EXPECT_FALSE(node->has_parameter(name)); } + { + // adding a parameter in "pre set parameter" callback when that + // parameter has not been declared before will throw and since + // multiple params are being set using "set_parameters_atomically", + // a failure in set of one param will result in all params being + // set unsuccessfully. + auto name1 = "parameter"_unq; + auto name2 = "parameter"_unq; + auto name3 = "parameter"_unq; + auto default_value = 0; + + // declare name1 and name2 parameter only + node->declare_parameter(name1, default_value); + node->declare_parameter(name2, default_value); + + // add undeclared parameter with name3 to modified list of parameters + // conditioned of name2 param + auto pre_set_parameters = + [&](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == name2) { + parameters.emplace_back(rclcpp::Parameter(name3, 3)); + } + } + }; + + auto handler = node->add_pre_set_parameters_callback(pre_set_parameters); + EXPECT_THROW( + node->set_parameters_atomically( + {rclcpp::Parameter(name1, 1), + rclcpp::Parameter(name2, 2)}), + rclcpp::exceptions::ParameterNotDeclaredException); + EXPECT_TRUE(node->has_parameter(name1)); + EXPECT_TRUE(node->has_parameter(name2)); + EXPECT_FALSE(node->has_parameter(name3)); + + // the values of all the params is still default. + EXPECT_EQ(node->get_parameter(name1).get_value(), default_value); + EXPECT_EQ(node->get_parameter(name2).get_value(), default_value); + RCPPUTILS_SCOPE_EXIT( + {node->remove_pre_set_parameters_callback(handler.get());}); // always reset + } } // test set_parameters with undeclared allowed @@ -1903,6 +2160,45 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_allowed) { EXPECT_FALSE(node->has_parameter(name2)); // important! name2 remains undeclared EXPECT_EQ(node->get_parameter(name3).get_value(), "test"); } + { + // adding a parameter in "pre set parameter" callback when that + // parameter has not been declared before will not throw when + // undeclared parameters are allowed. + auto name1 = "parameter"_unq; + auto name2 = "parameter"_unq; + auto name3 = "parameter"_unq; + auto default_value = 0; + + // declare name1 and name2 parameter only + node->declare_parameter(name1, default_value); + node->declare_parameter(name2, default_value); + + // add undeclared parameter with name3 to modified list of parameters + // conditioned of name2 param + auto pre_set_parameters = + [&](std::vector & parameters) { + for (const auto & param : parameters) { + if (param.get_name() == name2) { + parameters.emplace_back(rclcpp::Parameter(name3, 3)); + } + } + }; + + auto handler = node->add_pre_set_parameters_callback(pre_set_parameters); + auto result = node->set_parameters_atomically( + {rclcpp::Parameter(name1, 1), + rclcpp::Parameter(name2, 2)}); + EXPECT_TRUE(result.successful); + EXPECT_TRUE(node->has_parameter(name1)); + EXPECT_TRUE(node->has_parameter(name2)); + EXPECT_TRUE(node->has_parameter(name3)); + EXPECT_EQ(node->get_parameter(name1).get_value(), 1); + EXPECT_EQ(node->get_parameter(name2).get_value(), 2); + EXPECT_EQ(node->get_parameter(name3).get_value(), 3); + + RCPPUTILS_SCOPE_EXIT( + {node->remove_pre_set_parameters_callback(handler.get());}); // always reset + } } // test get_parameter with undeclared not allowed @@ -3118,6 +3414,9 @@ TEST_F(TestNode, static_and_dynamic_typing) { EXPECT_THROW( node->get_parameter("integer_override_not_given"), rclcpp::exceptions::ParameterUninitializedException); + EXPECT_THROW( + node->get_parameters({"integer_override_not_given"}), + rclcpp::exceptions::ParameterUninitializedException); } { auto param = node->declare_parameter("integer_set_after_declare", rclcpp::PARAMETER_INTEGER); @@ -3139,3 +3438,34 @@ TEST_F(TestNode, static_and_dynamic_typing) { rclcpp::exceptions::InvalidParameterTypeException); } } + +TEST_F(TestNode, parameter_uninitialized_exception_even_if_allow_undeclared) { + rclcpp::NodeOptions no; + no.allow_undeclared_parameters(true); + auto node = std::make_shared("node", "ns", no); + { + const std::string param_name = "integer_override_not_given"; + auto param_value = node->declare_parameter(param_name, rclcpp::PARAMETER_INTEGER); + EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, param_value.get_type()); + // Throws if not set before access + EXPECT_THROW( + node->get_parameter(param_name), + rclcpp::exceptions::ParameterUninitializedException); + EXPECT_THROW( + node->get_parameters({param_name}), + rclcpp::exceptions::ParameterUninitializedException); + } +} + +TEST_F(TestNode, get_parameter_with_node_allow_undeclared) { + rclcpp::NodeOptions no; + no.allow_undeclared_parameters(true); + auto node = std::make_shared("node", "ns", no); + { + const std::string param_name = "allow_undeclared_param"; + auto param = node->get_parameter(param_name); + EXPECT_EQ(param_name, param.get_name()); + EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, param.get_type()); + EXPECT_EQ(rclcpp::ParameterValue{}, param.get_parameter_value()); + } +} diff --git a/rclcpp/test/rclcpp/test_node_options.cpp b/rclcpp/test/rclcpp/test_node_options.cpp index 3fd0a0d52b..2468923229 100644 --- a/rclcpp/test/rclcpp/test_node_options.cpp +++ b/rclcpp/test/rclcpp/test_node_options.cpp @@ -316,3 +316,12 @@ TEST(TestNodeOptions, set_get_allocator) { // Check invalid allocator EXPECT_THROW(options.get_rcl_node_options(), std::bad_alloc); } + +TEST(TestNodeOptions, clock_type) { + rclcpp::NodeOptions options; + EXPECT_EQ(RCL_ROS_TIME, options.clock_type()); + options.clock_type(RCL_SYSTEM_TIME); + EXPECT_EQ(RCL_SYSTEM_TIME, options.clock_type()); + options.clock_type(RCL_STEADY_TIME); + EXPECT_EQ(RCL_STEADY_TIME, options.clock_type()); +} diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index cf69dd8ded..e3198e153c 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include @@ -440,6 +440,7 @@ TEST_F(TestParameterClient, sync_parameter_get_parameter_types_allow_undeclared) TEST_F(TestParameterClient, sync_parameter_get_parameters) { node->declare_parameter("foo", 4); node->declare_parameter("bar", "this is bar"); + node->declare_parameter("baz", rclcpp::PARAMETER_INTEGER); auto synchronous_client = std::make_shared(node); { @@ -448,6 +449,14 @@ TEST_F(TestParameterClient, sync_parameter_get_parameters) { ASSERT_EQ(0u, parameters.size()); } + { + // not throw ParameterUninitializedException while getting parameter from service + // even if the parameter is not initialized in the node + std::vector names{"baz"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(0u, parameters.size()); + } + { std::vector names{"none", "foo", "bar"}; std::vector parameters = synchronous_client->get_parameters(names, 10s); @@ -487,6 +496,7 @@ TEST_F(TestParameterClient, sync_parameter_get_parameters) { TEST_F(TestParameterClient, sync_parameter_get_parameters_allow_undeclared) { node_with_option->declare_parameter("foo", 4); node_with_option->declare_parameter("bar", "this is bar"); + node_with_option->declare_parameter("baz", rclcpp::PARAMETER_INTEGER); auto synchronous_client = std::make_shared(node_with_option); { @@ -495,6 +505,14 @@ TEST_F(TestParameterClient, sync_parameter_get_parameters_allow_undeclared) { ASSERT_EQ(1u, parameters.size()); } + { + // not throw ParameterUninitializedException while getting parameter from service + // even if the parameter is not initialized in the node + std::vector names{"baz"}; + std::vector parameters = synchronous_client->get_parameters(names, 10s); + ASSERT_EQ(0u, parameters.size()); + } + { std::vector names{"none", "foo", "bar"}; std::vector parameters = synchronous_client->get_parameters(names, 10s); @@ -948,3 +966,138 @@ TEST_F(TestParameterClient, sync_parameter_load_parameters) { auto list_parameters = synchronous_client->list_parameters({}, 3); ASSERT_EQ(list_parameters.names.size(), static_cast(5)); } + +/* + Coverage for async load_parameters with complicated regex expression + */ +TEST_F(TestParameterClient, async_parameter_load_parameters_complicated_regex) { + auto load_node = std::make_shared( + "load_node", + "namespace", + rclcpp::NodeOptions().allow_undeclared_parameters(true)); + auto asynchronous_client = + std::make_shared(load_node, "/namespace/load_node"); + // load parameters + rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY}; + const std::string parameters_filepath = ( + test_resources_path / "test_node" / "load_complicated_parameters.yaml").string(); + auto load_future = asynchronous_client->load_parameters(parameters_filepath); + auto result_code = rclcpp::spin_until_future_complete( + load_node, load_future, std::chrono::milliseconds(100)); + ASSERT_EQ(result_code, rclcpp::FutureReturnCode::SUCCESS); + ASSERT_EQ(load_future.get()[0].successful, true); + // list parameters + auto list_parameters = asynchronous_client->list_parameters({}, 3); + rclcpp::spin_until_future_complete( + load_node, list_parameters, std::chrono::milliseconds(100)); + ASSERT_EQ(list_parameters.get().names.size(), static_cast(6)); + // to check the parameter "a_value" + std::string param_name = "a_value"; + auto param = load_node->get_parameter(param_name); + ASSERT_EQ(param.get_value(), "last_one_win"); +} + +/* + Coverage for async load_parameters to load file without valid parameters + */ +TEST_F(TestParameterClient, async_parameter_load_no_valid_parameter) { + auto load_node = std::make_shared( + "load_node", + "namespace", + rclcpp::NodeOptions().allow_undeclared_parameters(true)); + auto asynchronous_client = + std::make_shared(load_node, "/namespace/load_node"); + // load parameters + rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY}; + const std::string parameters_filepath = ( + test_resources_path / "test_node" / "no_valid_parameters.yaml").string(); + EXPECT_THROW( + asynchronous_client->load_parameters(parameters_filepath), + rclcpp::exceptions::InvalidParametersException); +} + +/* + Coverage for async load_parameters from maps with complicated regex expression + */ +TEST_F(TestParameterClient, async_parameter_load_parameters_from_map) { + auto load_node = std::make_shared( + "load_node", + "namespace", + rclcpp::NodeOptions().allow_undeclared_parameters(true)); + auto asynchronous_client = + std::make_shared(load_node, "/namespace/load_node"); + // load parameters + rclcpp::ParameterMap parameter_map = { + {"/**", + { + {"bar", 5}, + {"foo", 3.5}, + {"a_value", "first"} + } + }, + {"/*/load_node", + { + {"bar_foo", "ok"}, + {"a_value", "second"} + } + }, + {"/namespace/load_node", + { + {"foo_bar", true}, + {"a_value", "third"} + } + }, + {"/bar", + { + {"fatal", 10} + } + }, + {"/**/namespace/*", + { + {"a_value", "not_win"} + } + } + }; + + auto load_future = asynchronous_client->load_parameters(parameter_map); + auto result_code = rclcpp::spin_until_future_complete( + load_node, load_future, std::chrono::milliseconds(100)); + ASSERT_EQ(result_code, rclcpp::FutureReturnCode::SUCCESS); + ASSERT_EQ(load_future.get()[0].successful, true); + // list parameters + auto list_parameters = asynchronous_client->list_parameters({}, 3); + rclcpp::spin_until_future_complete( + load_node, list_parameters, std::chrono::milliseconds(100)); + ASSERT_EQ(list_parameters.get().names.size(), static_cast(6)); + // to check the parameter "a_value" + std::string param_name = "a_value"; + auto param = load_node->get_parameter(param_name); + // rclcpp::ParameterMap is an unordered map, no guarantee which value will be set for `a_value`. + EXPECT_THAT( + (std::array{"first", "second", "third", "not_win"}), + testing::Contains(param.get_value())); +} + +/* + Coverage for async load_parameters from maps without valid parameters + */ +TEST_F(TestParameterClient, async_parameter_load_from_map_no_valid_parameter) { + auto load_node = std::make_shared( + "load_node", + "namespace", + rclcpp::NodeOptions().allow_undeclared_parameters(true)); + auto asynchronous_client = + std::make_shared(load_node, "/namespace/load_node"); + // load parameters + rclcpp::ParameterMap parameter_map = { + {"/no/valid/parameters/node", + { + {"bar", 5}, + {"bar", 3.5} + } + } + }; + EXPECT_THROW( + asynchronous_client->load_parameters(parameter_map), + rclcpp::exceptions::InvalidParametersException); +} diff --git a/rclcpp/test/rclcpp/test_parameter_map.cpp b/rclcpp/test/rclcpp/test_parameter_map.cpp index 3f54e4c879..0158b7c7e7 100644 --- a/rclcpp/test/rclcpp/test_parameter_map.cpp +++ b/rclcpp/test/rclcpp/test_parameter_map.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include "rclcpp/parameter_map.hpp" @@ -353,3 +354,132 @@ TEST(Test_parameter_map_from, string_array_param_value) c_params->params[0].parameter_values[0].string_array_value = NULL; rcl_yaml_node_struct_fini(c_params); } + +TEST(Test_parameter_map_from, one_node_one_param_by_node_fqn) +{ + rcl_params_t * c_params = make_params({"foo"}); + make_node_params(c_params, 0, {"string_param"}); + + std::string hello_world = "hello world"; + char * c_hello_world = new char[hello_world.length() + 1]; + std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str()); + c_params->params[0].parameter_values[0].string_value = c_hello_world; + + rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params, "/foo"); + const std::vector & params = map.at("/foo"); + EXPECT_STREQ("string_param", params.at(0).get_name().c_str()); + EXPECT_STREQ(hello_world.c_str(), params.at(0).get_value().c_str()); + + c_params->params[0].parameter_values[0].string_value = NULL; + delete[] c_hello_world; + rcl_yaml_node_struct_fini(c_params); +} + +TEST(Test_parameter_map_from, multi_nodes_same_param_name_by_node_fqn) +{ + std::vector node_names_keys = { + "/**", // index: 0 + "/*", // index: 1 + "/**/node", // index: 2 + "/*/node", // index: 3 + "/ns/node" // index: 4 + }; + + rcl_params_t * c_params = make_params(node_names_keys); + + std::vector param_values; + for (size_t i = 0; i < node_names_keys.size(); ++i) { + make_node_params(c_params, i, {"string_param"}); + std::string hello_world = "hello world" + std::to_string(i); + char * c_hello_world = new char[hello_world.length() + 1]; + std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str()); + c_params->params[i].parameter_values[0].string_value = c_hello_world; + param_values.push_back(c_hello_world); + } + + std::unordered_map> node_fqn_expected = { + {"/ns/foo/another_node", {0}}, + {"/another", {0, 1}}, + {"/node", {0, 1, 2}}, + {"/another_ns/node", {0, 2, 3}}, + {"/ns/node", {0, 2, 3, 4}}, + }; + + for (auto & kv : node_fqn_expected) { + rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params, kv.first.c_str()); + const std::vector & params = map.at(kv.first); + + EXPECT_EQ(kv.second.size(), params.size()); + for (size_t i = 0; i < params.size(); ++i) { + std::string param_value = "hello world" + std::to_string(kv.second[i]); + EXPECT_STREQ("string_param", params.at(i).get_name().c_str()); + EXPECT_STREQ(param_value.c_str(), params.at(i).get_value().c_str()); + } + } + + for (size_t i = 0; i < node_names_keys.size(); ++i) { + c_params->params[i].parameter_values[0].string_value = NULL; + } + for (auto c_hello_world : param_values) { + delete[] c_hello_world; + } + rcl_yaml_node_struct_fini(c_params); +} + +TEST(Test_parameter_map_from, multi_nodes_diff_param_name_by_node_fqn) +{ + std::vector node_names_keys = { + "/**", // index: 0 + "/*", // index: 1 + "/**/node", // index: 2 + "/*/node", // index: 3 + "/ns/**", // index: 4 + "/ns/*", // index: 5 + "/ns/**/node", // index: 6 + "/ns/*/node", // index: 7 + "/ns/**/a/*/node", // index: 8 + "/ns/node" // index: 9 + }; + + rcl_params_t * c_params = make_params(node_names_keys); + + for (size_t i = 0; i < node_names_keys.size(); ++i) { + std::string param_name = "string_param" + std::to_string(i); + make_node_params(c_params, i, {param_name}); + } + + std::string hello_world = "hello world"; + char * c_hello_world = new char[hello_world.length() + 1]; + std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str()); + + for (size_t i = 0; i < node_names_keys.size(); ++i) { + c_params->params[i].parameter_values[0].string_value = c_hello_world; + } + + std::unordered_map> node_fqn_expected = { + {"/ns/node", {0, 2, 3, 4, 5, 6, 9}}, + {"/node", {0, 1, 2}}, + {"/ns/foo/node", {0, 2, 4, 6, 7}}, + {"/ns/foo/a/node", {0, 2, 4, 6}}, + {"/ns/foo/a/bar/node", {0, 2, 4, 6, 8}}, + {"/ns/a/bar/node", {0, 2, 4, 6, 8}}, + {"/ns/foo/zoo/a/bar/node", {0, 2, 4, 6, 8}}, + }; + + for (auto & kv : node_fqn_expected) { + rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params, kv.first.c_str()); + const std::vector & params = map.at(kv.first); + EXPECT_EQ(kv.second.size(), params.size()); + for (size_t i = 0; i < params.size(); ++i) { + std::string param_name = "string_param" + std::to_string(kv.second[i]); + EXPECT_STREQ(param_name.c_str(), params.at(i).get_name().c_str()); + EXPECT_STREQ(hello_world.c_str(), params.at(i).get_value().c_str()); + } + } + + for (size_t i = 0; i < node_names_keys.size(); ++i) { + c_params->params[i].parameter_values[0].string_value = NULL; + } + delete[] c_hello_world; + rcl_yaml_node_struct_fini(c_params); +} diff --git a/rclcpp/test/rclcpp/test_publisher.cpp b/rclcpp/test/rclcpp/test_publisher.cpp index 35605230d9..5cffe1d5e1 100644 --- a/rclcpp/test/rclcpp/test_publisher.cpp +++ b/rclcpp/test/rclcpp/test_publisher.cpp @@ -245,10 +245,9 @@ const rosidl_message_type_support_t EmptyTypeSupport() return *rosidl_typesupport_cpp::get_message_type_support_handle(); } -const rcl_publisher_options_t PublisherOptions() +const rclcpp::PublisherOptionsWithAllocator> PublisherOptions() { - return rclcpp::PublisherOptionsWithAllocator>().template - to_rcl_publisher_options(rclcpp::QoS(10)); + return rclcpp::PublisherOptionsWithAllocator>(); } class TestPublisherBase : public rclcpp::PublisherBase @@ -256,7 +255,9 @@ class TestPublisherBase : public rclcpp::PublisherBase public: explicit TestPublisherBase(rclcpp::Node * node) : rclcpp::PublisherBase( - node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), PublisherOptions()) {} + node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), + PublisherOptions().to_rcl_publisher_options(rclcpp::QoS(10)), + PublisherOptions().event_callbacks, PublisherOptions().use_default_callbacks) {} }; /* diff --git a/rclcpp/test/rclcpp/test_qos_parameters.cpp b/rclcpp/test/rclcpp/test_qos_parameters.cpp index 97d524d176..be9a12cb5e 100644 --- a/rclcpp/test/rclcpp/test_qos_parameters.cpp +++ b/rclcpp/test/rclcpp/test_qos_parameters.cpp @@ -255,3 +255,9 @@ TEST(TestQosParameters, internal_functions_failure_modes) { nullptr, rclcpp::QosPolicyKind::Reliability), std::invalid_argument); } + +TEST(TestQosParameters, keep_last_zero) { + rclcpp::KeepLast keep_last(0); + + EXPECT_EQ(keep_last.depth, RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT); +} diff --git a/rclcpp/test/rclcpp/test_service.cpp b/rclcpp/test/rclcpp/test_service.cpp index 1dbb8ca9e4..a3c361cfde 100644 --- a/rclcpp/test/rclcpp/test_service.cpp +++ b/rclcpp/test/rclcpp/test_service.cpp @@ -246,8 +246,8 @@ TEST_F(TestService, on_new_request_callback) { auto server_callback = [](const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {FAIL();}; - rmw_qos_profile_t service_qos = rmw_qos_profile_services_default; - service_qos.depth = 3; + rclcpp::ServicesQoS service_qos; + service_qos.keep_last(3); auto server = node->create_service( "~/test_service", server_callback, service_qos); @@ -338,28 +338,25 @@ TEST_F(TestService, rcl_service_request_subscription_get_actual_qos_error) { TEST_F(TestService, server_qos) { - rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default; - qos_profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC; - uint64_t duration = 1; - qos_profile.deadline = {duration, duration}; - qos_profile.lifespan = {duration, duration}; - qos_profile.liveliness_lease_duration = {duration, duration}; + rclcpp::ServicesQoS qos_profile; + qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic); + rclcpp::Duration duration(std::chrono::nanoseconds(1)); + qos_profile.deadline(duration); + qos_profile.lifespan(duration); + qos_profile.liveliness_lease_duration(duration); auto callback = [](const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {}; auto server = node->create_service( - "service", callback, - qos_profile); - auto init_qos = - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile), qos_profile); + "service", callback, qos_profile); auto rs_qos = server->get_request_subscription_actual_qos(); auto rp_qos = server->get_response_publisher_actual_qos(); - EXPECT_EQ(init_qos, rp_qos); + EXPECT_EQ(qos_profile, rp_qos); // Lifespan has no meaning for subscription/readers - rs_qos.lifespan(qos_profile.lifespan); - EXPECT_EQ(init_qos, rs_qos); + rs_qos.lifespan(qos_profile.lifespan()); + EXPECT_EQ(qos_profile, rs_qos); } TEST_F(TestService, server_qos_depth) { @@ -372,13 +369,12 @@ TEST_F(TestService, server_qos_depth) { auto server_node = std::make_shared("server_node", "/ns"); - rmw_qos_profile_t server_qos_profile = rmw_qos_profile_default; - server_qos_profile.depth = 2; + rclcpp::QoS server_qos_profile(2); auto server = server_node->create_service( "test_qos_depth", std::move(server_callback), server_qos_profile); - rmw_qos_profile_t client_qos_profile = rmw_qos_profile_default; + rclcpp::QoS client_qos_profile(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); auto client = node->create_client("test_qos_depth", client_qos_profile); ::testing::AssertionResult request_result = ::testing::AssertionSuccess(); @@ -398,7 +394,7 @@ TEST_F(TestService, server_qos_depth) { } auto start = std::chrono::steady_clock::now(); - while ((server_cb_count_ < server_qos_profile.depth) && + while ((server_cb_count_ < server_qos_profile.depth()) && (std::chrono::steady_clock::now() - start) < 1s) { rclcpp::spin_some(server_node); @@ -409,5 +405,5 @@ TEST_F(TestService, server_qos_depth) { // so more server responses might be processed than expected. rclcpp::spin_some(server_node); - EXPECT_EQ(server_cb_count_, server_qos_profile.depth); + EXPECT_EQ(server_cb_count_, server_qos_profile.depth()); } diff --git a/rclcpp/test/rclcpp/test_time.cpp b/rclcpp/test/rclcpp/test_time.cpp index 2f188b2d7c..f3969d3886 100644 --- a/rclcpp/test/rclcpp/test_time.cpp +++ b/rclcpp/test/rclcpp/test_time.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include "rcl/error_handling.h" #include "rcl/time.h" @@ -848,3 +849,72 @@ TEST_F(TestClockSleep, sleep_for_basic_ros) { sleep_thread.join(); EXPECT_TRUE(sleep_succeeded); } + +class TestClockStarted : public ::testing::Test +{ +protected: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestClockStarted, started) { + // rclcpp::Clock ros_clock(RCL_ROS_TIME); + // auto ros_clock_handle = ros_clock.get_clock_handle(); + // + // // At this point, the ROS clock is reading system time since the ROS time override isn't on + // // So we expect it to be started (it's extremely unlikely that system time is at epoch start) + // EXPECT_TRUE(ros_clock.started()); + // EXPECT_TRUE(ros_clock.wait_until_started()); + // EXPECT_TRUE(ros_clock.wait_until_started(rclcpp::Duration(0, static_cast(1e7)))); + // EXPECT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(ros_clock_handle)); + // EXPECT_TRUE(ros_clock.ros_time_is_active()); + // EXPECT_FALSE(ros_clock.started()); + // EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(ros_clock_handle, 1)); + // EXPECT_TRUE(ros_clock.started()); + // + // rclcpp::Clock system_clock(RCL_SYSTEM_TIME); + // EXPECT_TRUE(system_clock.started()); + // EXPECT_TRUE(system_clock.wait_until_started()); + // EXPECT_TRUE(system_clock.wait_until_started(rclcpp::Duration(0, static_cast(1e7)))); + // + // rclcpp::Clock steady_clock(RCL_STEADY_TIME); + // EXPECT_TRUE(steady_clock.started()); + // EXPECT_TRUE(steady_clock.wait_until_started()); + // EXPECT_TRUE(steady_clock.wait_until_started(rclcpp::Duration(0, static_cast(1e7)))); + // + // rclcpp::Clock uninit_clock(RCL_CLOCK_UNINITIALIZED); + // RCLCPP_EXPECT_THROW_EQ( + // uninit_clock.started(), std::runtime_error("clock is not rcl_clock_valid")); + // RCLCPP_EXPECT_THROW_EQ( + // uninit_clock.wait_until_started(rclcpp::Duration(0, static_cast(1e7))), + // std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid")); +} + +TEST_F(TestClockStarted, started_timeout) { + rclcpp::Clock ros_clock(RCL_ROS_TIME); + auto ros_clock_handle = ros_clock.get_clock_handle(); + + EXPECT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(ros_clock_handle)); + EXPECT_TRUE(ros_clock.ros_time_is_active()); + + EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(ros_clock_handle, 0)); + + EXPECT_FALSE(ros_clock.started()); + EXPECT_FALSE(ros_clock.wait_until_started(rclcpp::Duration(0, static_cast(1e7)))); + + std::thread t([]() { + std::this_thread::sleep_for(std::chrono::seconds(1)); + rclcpp::shutdown(); + }); + + // Test rclcpp shutdown escape hatch (otherwise this waits indefinitely) + EXPECT_FALSE(ros_clock.wait_until_started()); + t.join(); +} diff --git a/rclcpp/test/rclcpp/test_time_source.cpp b/rclcpp/test/rclcpp/test_time_source.cpp index 2bf89a5b09..22aefcda3b 100644 --- a/rclcpp/test/rclcpp/test_time_source.cpp +++ b/rclcpp/test/rclcpp/test_time_source.cpp @@ -81,7 +81,7 @@ void spin_until_time( executor.spin_once(10ms); - if (clock->now().nanoseconds() == end_time.count()) { + if (clock->now().nanoseconds() >= end_time.count()) { return; } } @@ -108,7 +108,7 @@ void spin_until_ros_time_updated( executor.add_node(node); auto start = std::chrono::system_clock::now(); - while (std::chrono::system_clock::now() < (start + 1s)) { + while (std::chrono::system_clock::now() < (start + 2s)) { if (!rclcpp::ok()) { break; // Break for ctrl-c } @@ -267,6 +267,35 @@ TEST(TimeSource, invalid_sim_time_parameter_override) rclcpp::shutdown(); } +TEST(TimeSource, valid_clock_type_for_sim_time) +{ + rclcpp::init(0, nullptr); + + rclcpp::NodeOptions options; + auto node = std::make_shared("my_node", options); + EXPECT_TRUE( + node->set_parameter( + rclcpp::Parameter( + "use_sim_time", rclcpp::ParameterValue( + true))).successful); + rclcpp::shutdown(); +} + +TEST(TimeSource, invalid_clock_type_for_sim_time) +{ + rclcpp::init(0, nullptr); + + rclcpp::NodeOptions options; + options.clock_type(RCL_STEADY_TIME); + auto node = std::make_shared("my_node", options); + EXPECT_FALSE( + node->set_parameter( + rclcpp::Parameter( + "use_sim_time", rclcpp::ParameterValue( + true))).successful); + rclcpp::shutdown(); +} + TEST_F(TestTimeSource, clock) { rclcpp::TimeSource ts(node); auto ros_clock = std::make_shared(RCL_ROS_TIME); @@ -630,7 +659,8 @@ class SimClockPublisherNode : public rclcpp::Node { public: SimClockPublisherNode() - : rclcpp::Node("sim_clock_publisher_node") + : rclcpp::Node("sim_clock_publisher_node"), + pub_time_(0, 0) { // Create a clock publisher clock_pub_ = this->create_publisher( @@ -645,10 +675,6 @@ class SimClockPublisherNode : public rclcpp::Node &SimClockPublisherNode::timer_callback, this) ); - - // Init clock msg to zero - clock_msg_.clock.sec = 0; - clock_msg_.clock.nanosec = 0; } ~SimClockPublisherNode() @@ -671,13 +697,15 @@ class SimClockPublisherNode : public rclcpp::Node private: void timer_callback() { - // Increment clock msg and publish it - clock_msg_.clock.nanosec += 1000000; + // Increment the time, update the clock msg and publish it + pub_time_ += rclcpp::Duration(0, 1000000); + clock_msg_.clock = pub_time_; clock_pub_->publish(clock_msg_); } rclcpp::Publisher::SharedPtr clock_pub_; rclcpp::TimerBase::SharedPtr pub_timer_; + rclcpp::Time pub_time_; rosgraph_msgs::msg::Clock clock_msg_; std::thread node_thread_; rclcpp::executors::SingleThreadedExecutor node_executor; @@ -695,7 +723,7 @@ class ClockThreadTestingNode : public rclcpp::Node this->set_parameter(rclcpp::Parameter("use_sim_time", true)); // Create a 100ms timer - timer_ = this->create_wall_timer( + timer_ = this->create_timer( std::chrono::milliseconds(100), std::bind( &ClockThreadTestingNode::timer_callback, @@ -735,29 +763,33 @@ class ClockThreadTestingNode : public rclcpp::Node bool is_callback_frozen_ = true; }; -TEST_F(TestTimeSource, check_sim_time_updated_in_callback_if_use_clock_thread) { - // Test if clock time of a node with - // parameter use_sim_time = true and option use_clock_thread = true - // is updated while node is not spinning - // (in a timer callback) - - // Create a "sim time" publisher and spin it - SimClockPublisherNode pub_node; - pub_node.SpinNode(); - - // Spin node for 2 seconds - ClockThreadTestingNode clock_thread_testing_node; - auto steady_clock = rclcpp::Clock(RCL_STEADY_TIME); - auto start_time = steady_clock.now(); - while (rclcpp::ok() && - (steady_clock.now() - start_time).seconds() < 2.0) - { - rclcpp::spin_some(clock_thread_testing_node.get_node_base_interface()); - } - - // Node should have get out of timer callback - ASSERT_FALSE(clock_thread_testing_node.GetIsCallbackFrozen()); -} +// TODO(ivanpauno): This test was using a wall timer, when it was supposed to use sim time. +// It was also using `use_clock_tread = false`, when it was supposed to be `true`. +// Fixing the test to work as originally intended makes it super flaky. +// Disabling it until the test is fixed. +// TEST_F(TestTimeSource, check_sim_time_updated_in_callback_if_use_clock_thread) { +// // Test if clock time of a node with +// // parameter use_sim_time = true and option use_clock_thread = true +// // is updated while node is not spinning +// // (in a timer callback) + +// // Create a "sim time" publisher and spin it +// SimClockPublisherNode pub_node; +// pub_node.SpinNode(); + +// // Spin node for 2 seconds +// ClockThreadTestingNode clock_thread_testing_node; +// auto steady_clock = rclcpp::Clock(RCL_STEADY_TIME); +// auto start_time = steady_clock.now(); +// while (rclcpp::ok() && +// (steady_clock.now() - start_time).seconds() < 2.0) +// { +// rclcpp::spin_some(clock_thread_testing_node.get_node_base_interface()); +// } + +// // Node should have get out of timer callback +// ASSERT_FALSE(clock_thread_testing_node.GetIsCallbackFrozen()); +// } TEST_F(TestTimeSource, clock_sleep_until_with_ros_time_basic) { SimClockPublisherNode pub_node; diff --git a/rclcpp/test/rclcpp/test_timer.cpp b/rclcpp/test/rclcpp/test_timer.cpp index 7a6599dfe4..59a1218519 100644 --- a/rclcpp/test/rclcpp/test_timer.cpp +++ b/rclcpp/test/rclcpp/test_timer.cpp @@ -30,8 +30,15 @@ using namespace std::chrono_literals; +/// We want to test everything for both the wall and generic timer. +enum class TimerType +{ + WALL_TIMER, + GENERIC_TIMER, +}; + /// Timer testing bring up and teardown -class TestTimer : public ::testing::Test +class TestTimer : public ::testing::TestWithParam { protected: void SetUp() override @@ -44,10 +51,7 @@ class TestTimer : public ::testing::Test test_node = std::make_shared("test_timer_node"); - timer = test_node->create_wall_timer( - 100ms, - [this]() -> void - { + auto timer_callback = [this]() -> void { this->has_timer_run.store(true); if (this->cancel_timer.load()) { @@ -55,10 +59,20 @@ class TestTimer : public ::testing::Test } // prevent any tests running timer from blocking this->executor->cancel(); - } - ); - EXPECT_TRUE(timer->is_steady()); - + }; + + // Store the timer type for use in TEST_P declarations. + timer_type = GetParam(); + switch (timer_type) { + case TimerType::WALL_TIMER: + timer = test_node->create_wall_timer(100ms, timer_callback); + EXPECT_TRUE(timer->is_steady()); + break; + case TimerType::GENERIC_TIMER: + timer = test_node->create_timer(100ms, timer_callback); + EXPECT_FALSE(timer->is_steady()); + break; + } executor->add_node(test_node); // don't start spinning, let the test dictate when } @@ -72,6 +86,7 @@ class TestTimer : public ::testing::Test } // set to true if the timer callback executed, false otherwise + TimerType timer_type; std::atomic has_timer_run; // flag used to cancel the timer in the timer callback. If true cancel the timer, otherwise // cancel the executor (preventing any tests from blocking) @@ -91,7 +106,7 @@ void test_initial_conditions( } /// Simple test -TEST_F(TestTimer, test_simple_cancel) +TEST_P(TestTimer, test_simple_cancel) { // expect clean state, don't run otherwise test_initial_conditions(timer, has_timer_run); @@ -104,7 +119,7 @@ TEST_F(TestTimer, test_simple_cancel) } /// Test state when using reset -TEST_F(TestTimer, test_is_canceled_reset) +TEST_P(TestTimer, test_is_canceled_reset) { // expect clean state, don't run otherwise test_initial_conditions(timer, has_timer_run); @@ -129,7 +144,7 @@ TEST_F(TestTimer, test_is_canceled_reset) } /// Run and check state, cancel the executor -TEST_F(TestTimer, test_run_cancel_executor) +TEST_P(TestTimer, test_run_cancel_executor) { // expect clean state, don't run otherwise test_initial_conditions(timer, has_timer_run); @@ -146,7 +161,7 @@ TEST_F(TestTimer, test_run_cancel_executor) } /// Run and check state, cancel the timer -TEST_F(TestTimer, test_run_cancel_timer) +TEST_P(TestTimer, test_run_cancel_timer) { // expect clean state, don't run otherwise test_initial_conditions(timer, has_timer_run); @@ -159,7 +174,7 @@ TEST_F(TestTimer, test_run_cancel_timer) EXPECT_TRUE(timer->is_canceled()); } -TEST_F(TestTimer, test_bad_arguments) { +TEST_P(TestTimer, test_bad_arguments) { auto node_base = rclcpp::node_interfaces::get_node_base_interface(test_node); auto context = node_base->get_context(); @@ -198,13 +213,19 @@ TEST_F(TestTimer, test_bad_arguments) { rclcpp::exceptions::RCLError); } -TEST_F(TestTimer, callback_with_timer) { +TEST_P(TestTimer, callback_with_timer) { rclcpp::TimerBase * timer_ptr = nullptr; - timer = test_node->create_wall_timer( - std::chrono::milliseconds(1), - [&timer_ptr](rclcpp::TimerBase & timer) { + auto timer_callback = [&timer_ptr](rclcpp::TimerBase & timer) { timer_ptr = &timer; - }); + }; + switch (timer_type) { + case TimerType::WALL_TIMER: + timer = test_node->create_wall_timer(1ms, timer_callback); + break; + case TimerType::GENERIC_TIMER: + timer = test_node->create_timer(1ms, timer_callback); + break; + } auto start = std::chrono::steady_clock::now(); while (nullptr == timer_ptr && (std::chrono::steady_clock::now() - start) < std::chrono::milliseconds(100)) @@ -216,13 +237,19 @@ TEST_F(TestTimer, callback_with_timer) { EXPECT_FALSE(timer_ptr->is_ready()); } -TEST_F(TestTimer, callback_with_period_zero) { +TEST_P(TestTimer, callback_with_period_zero) { rclcpp::TimerBase * timer_ptr = nullptr; - timer = test_node->create_wall_timer( - std::chrono::milliseconds(0), - [&timer_ptr](rclcpp::TimerBase & timer) { + auto timer_callback = [&timer_ptr](rclcpp::TimerBase & timer) { timer_ptr = &timer; - }); + }; + switch (timer_type) { + case TimerType::WALL_TIMER: + timer = test_node->create_wall_timer(0ms, timer_callback); + break; + case TimerType::GENERIC_TIMER: + timer = test_node->create_timer(0ms, timer_callback); + break; + } auto start = std::chrono::steady_clock::now(); while (nullptr == timer_ptr && (std::chrono::steady_clock::now() - start) < std::chrono::milliseconds(100)) @@ -235,7 +262,7 @@ TEST_F(TestTimer, callback_with_period_zero) { } /// Test internal failures using mocks -TEST_F(TestTimer, test_failures_with_exceptions) +TEST_P(TestTimer, test_failures_with_exceptions) { // expect clean state, don't run otherwise test_initial_conditions(timer, has_timer_run); @@ -245,8 +272,16 @@ TEST_F(TestTimer, test_failures_with_exceptions) auto mock = mocking_utils::inject_on_return("lib:rclcpp", rcl_timer_fini, RCL_RET_ERROR); EXPECT_NO_THROW( { - timer_to_test_destructor = - test_node->create_wall_timer(std::chrono::milliseconds(0), [](void) {}); + switch (timer_type) { + case TimerType::WALL_TIMER: + timer_to_test_destructor = + test_node->create_wall_timer(std::chrono::milliseconds(0), [](void) {}); + break; + case TimerType::GENERIC_TIMER: + timer_to_test_destructor = + test_node->create_timer(std::chrono::milliseconds(0), [](void) {}); + break; + } timer_to_test_destructor.reset(); }); } @@ -283,3 +318,19 @@ TEST_F(TestTimer, test_failures_with_exceptions) std::runtime_error("Timer could not get time until next call: error not set")); } } + +INSTANTIATE_TEST_SUITE_P( + PerTimerType, TestTimer, + ::testing::Values(TimerType::WALL_TIMER, TimerType::GENERIC_TIMER), + [](const ::testing::TestParamInfo & info) -> std::string { + switch (info.param) { + case TimerType::WALL_TIMER: + return std::string("wall_timer"); + case TimerType::GENERIC_TIMER: + return std::string("generic_timer"); + default: + break; + } + return std::string("unknown"); + } +); diff --git a/rclcpp/test/rclcpp/test_type_support.cpp b/rclcpp/test/rclcpp/test_type_support.cpp index 1732031029..682907e2a9 100644 --- a/rclcpp/test/rclcpp/test_type_support.cpp +++ b/rclcpp/test/rclcpp/test_type_support.cpp @@ -58,10 +58,9 @@ class TestTypeSupport : public ::testing::Test rclcpp::Node::SharedPtr node = std::make_shared("my_node", "/ns"); }; -const rcl_publisher_options_t PublisherOptions() +const rclcpp::PublisherOptionsWithAllocator> PublisherOptions() { - return rclcpp::PublisherOptionsWithAllocator>().template - to_rcl_publisher_options(rclcpp::QoS(10)); + return rclcpp::PublisherOptionsWithAllocator>(); } // Auxiliary classes used to test rosidl_message_type_support_t getters @@ -77,7 +76,8 @@ class TestTSParameterEvent : public rclcpp::PublisherBase node->get_node_base_interface().get(), "topicTSParameterEvent", *ts_parameter_event, - PublisherOptions()) {} + PublisherOptions().to_rcl_publisher_options(rclcpp::QoS(10)), + PublisherOptions().event_callbacks, PublisherOptions().use_default_callbacks) {} }; const rosidl_message_type_support_t * ts_set_parameter_result = @@ -91,7 +91,8 @@ class TestTSSetParameterResult : public rclcpp::PublisherBase node->get_node_base_interface().get(), "topicTSSetParameterResult", *ts_set_parameter_result, - PublisherOptions()) {} + PublisherOptions().to_rcl_publisher_options(rclcpp::QoS(10)), + PublisherOptions().event_callbacks, PublisherOptions().use_default_callbacks) {} }; const rosidl_message_type_support_t * ts_parameter_descriptor = @@ -105,7 +106,8 @@ class TestTSParameterDescriptor : public rclcpp::PublisherBase node->get_node_base_interface().get(), "topicTSParameterDescriptor", *ts_parameter_descriptor, - PublisherOptions()) {} + PublisherOptions().to_rcl_publisher_options(rclcpp::QoS(10)), + PublisherOptions().event_callbacks, PublisherOptions().use_default_callbacks) {} }; const rosidl_message_type_support_t * ts_list_parameter_result = @@ -119,7 +121,8 @@ class TestTSListParametersResult : public rclcpp::PublisherBase node->get_node_base_interface().get(), "topicTSListParametersResult", *ts_list_parameter_result, - PublisherOptions()) {} + PublisherOptions().to_rcl_publisher_options(rclcpp::QoS(10)), + PublisherOptions().event_callbacks, PublisherOptions().use_default_callbacks) {} }; /* diff --git a/rclcpp/test/resources/test_node/load_complicated_parameters.yaml b/rclcpp/test/resources/test_node/load_complicated_parameters.yaml new file mode 100644 index 0000000000..7722f636c2 --- /dev/null +++ b/rclcpp/test/resources/test_node/load_complicated_parameters.yaml @@ -0,0 +1,25 @@ +/**: + ros__parameters: + bar: 5 + foo: 3.5 + a_value: "first" + +/*: + load_node: + ros__parameters: + bar_foo: "ok" + a_value: "second" + +namespace: + load_node: + ros__parameters: + foo_bar: true + a_value: "third" + +bar: + ros__parameters: + fatal: 10 + +/**/namespace/*: + ros__parameters: + a_value: "last_one_win" diff --git a/rclcpp/test/resources/test_node/no_valid_parameters.yaml b/rclcpp/test/resources/test_node/no_valid_parameters.yaml new file mode 100644 index 0000000000..a75356cd77 --- /dev/null +++ b/rclcpp/test/resources/test_node/no_valid_parameters.yaml @@ -0,0 +1,4 @@ +/no/valid/parameters/node: + ros__parameters: + bar: 5 + foo: 3.5 diff --git a/rclcpp/test/resources/test_node_parameters/complicated_wildcards.yaml b/rclcpp/test/resources/test_node_parameters/complicated_wildcards.yaml new file mode 100644 index 0000000000..53da409135 --- /dev/null +++ b/rclcpp/test/resources/test_node_parameters/complicated_wildcards.yaml @@ -0,0 +1,5 @@ +/**/foo/*/bar: + node2: + ros__parameters: + foo: "foo" + bar: "bar" diff --git a/rclcpp/test/resources/test_node_parameters/params_by_order.yaml b/rclcpp/test/resources/test_node_parameters/params_by_order.yaml new file mode 100644 index 0000000000..680d96beaf --- /dev/null +++ b/rclcpp/test/resources/test_node_parameters/params_by_order.yaml @@ -0,0 +1,16 @@ +/**: + node2: + ros__parameters: + a_value: "first" + foo: "foo" + +/ns: + node2: + ros__parameters: + a_value: "second" + bar: "bar" + +/*: + node2: + ros__parameters: + a_value: "last_one_win" diff --git a/rclcpp/test/resources/test_node_parameters/wildcards.yaml b/rclcpp/test/resources/test_node_parameters/wildcards.yaml new file mode 100644 index 0000000000..b89b0d8cd0 --- /dev/null +++ b/rclcpp/test/resources/test_node_parameters/wildcards.yaml @@ -0,0 +1,57 @@ +/**: + ros__parameters: + full_wild: "full_wild" + +/**: + node2: + ros__parameters: + namespace_wild: "namespace_wild" + +/**/node2: + ros__parameters: + namespace_wild_another: "namespace_wild_another" + +/*: + node2: + ros__parameters: + namespace_wild_one_star: "namespace_wild_one_star" + +ns: + "*": + ros__parameters: + node_wild_in_ns: "node_wild_in_ns" + +/ns/*: + ros__parameters: + node_wild_in_ns_another: "node_wild_in_ns_another" + +ns: + node2: + ros__parameters: + explicit_in_ns: "explicit_in_ns" + +"*": + ros__parameters: + node_wild_no_ns: "node_wild_no_ns" + +node2: + ros__parameters: + explicit_no_ns: "explicit_no_ns" + +ns: + nodeX: + ros__parameters: + should_not_appear: "incorrect_node_name" + +/**/nodeX: + ros__parameters: + should_not_appear: "incorrect_node_name" + +nsX: + node2: + ros__parameters: + should_not_appear: "incorrect_namespace" + +/nsX/*: + ros__parameters: + should_not_appear: "incorrect_namespace" diff --git a/rclcpp_action/CHANGELOG.rst b/rclcpp_action/CHANGELOG.rst index 9838922b49..2a08ebe63f 100644 --- a/rclcpp_action/CHANGELOG.rst +++ b/rclcpp_action/CHANGELOG.rst @@ -3,6 +3,23 @@ Changelog for package rclcpp_action ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +18.0.0 (2022-12-29) +------------------- +* Explicitly set callback type (`#2059 `_) +* Update maintainers (`#2043 `_) +* Contributors: Audrow Nash, mauropasse + +17.1.0 (2022-11-02) +------------------- +* Do not clear entities callbacks on destruction (`#2002 `_) +* Contributors: mauropasse + +17.0.0 (2022-09-13) +------------------- +* Revert "Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 `_) (`#1874 `_)" (`#1956 `_) +* Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 `_) (`#1874 `_) +* Contributors: Hubert Liberacki, William Woodall + 16.2.0 (2022-05-03) ------------------- diff --git a/rclcpp_action/package.xml b/rclcpp_action/package.xml index dd6e61338c..375e978be1 100644 --- a/rclcpp_action/package.xml +++ b/rclcpp_action/package.xml @@ -2,13 +2,17 @@ rclcpp_action - 16.2.0 + 18.0.0 Adds action APIs for C++. + Ivan Paunovic - Jacob Perron + Michel Hidalgo William Woodall + Apache License 2.0 + Dirk Thomas + Jacob Perron ament_cmake_ros diff --git a/rclcpp_action/src/client.cpp b/rclcpp_action/src/client.cpp index f9144ecf49..e687ab3400 100644 --- a/rclcpp_action/src/client.cpp +++ b/rclcpp_action/src/client.cpp @@ -136,7 +136,6 @@ ClientBase::ClientBase( ClientBase::~ClientBase() { - clear_on_ready_callback(); } bool @@ -434,7 +433,7 @@ ClientBase::set_callback_to_entity( // been replaced but the middleware hasn't been told about the new one yet. set_on_ready_callback( entity_type, - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline, static_cast(&new_callback)); std::lock_guard lock(listener_mutex_); @@ -454,7 +453,7 @@ ClientBase::set_callback_to_entity( auto & cb = it->second; set_on_ready_callback( entity_type, - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampolinesecond), const void *, size_t>, static_cast(&cb)); } diff --git a/rclcpp_action/src/server.cpp b/rclcpp_action/src/server.cpp index b0afb9aa50..c0fa96a88e 100644 --- a/rclcpp_action/src/server.cpp +++ b/rclcpp_action/src/server.cpp @@ -132,7 +132,6 @@ ServerBase::ServerBase( ServerBase::~ServerBase() { - clear_on_ready_callback(); } size_t @@ -746,7 +745,7 @@ ServerBase::set_callback_to_entity( // been replaced but the middleware hasn't been told about the new one yet. set_on_ready_callback( entity_type, - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampoline, static_cast(&new_callback)); std::lock_guard lock(listener_mutex_); @@ -766,7 +765,7 @@ ServerBase::set_callback_to_entity( auto & cb = it->second; set_on_ready_callback( entity_type, - rclcpp::detail::cpp_callback_trampoline, + rclcpp::detail::cpp_callback_trampolinesecond), const void *, size_t>, static_cast(&cb)); } diff --git a/rclcpp_components/CHANGELOG.rst b/rclcpp_components/CHANGELOG.rst index 805592a07f..820be8b817 100644 --- a/rclcpp_components/CHANGELOG.rst +++ b/rclcpp_components/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package rclcpp_components ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +18.0.0 (2022-12-29) +------------------- +* Update maintainers (`#2043 `_) +* Contributors: Audrow Nash + +17.1.0 (2022-11-02) +------------------- +* use unique ptr and remove unuseful container (`#2013 `_) +* Contributors: Chen Lihui + +17.0.0 (2022-09-13) +------------------- +* Revert "Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 `_) (`#1874 `_)" (`#1956 `_) +* Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 `_) (`#1874 `_) +* Contributors: Hubert Liberacki, William Woodall + 16.2.0 (2022-05-03) ------------------- diff --git a/rclcpp_components/include/rclcpp_components/component_manager_isolated.hpp b/rclcpp_components/include/rclcpp_components/component_manager_isolated.hpp index ea77532312..e2061e4da2 100644 --- a/rclcpp_components/include/rclcpp_components/component_manager_isolated.hpp +++ b/rclcpp_components/include/rclcpp_components/component_manager_isolated.hpp @@ -38,6 +38,16 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager { std::shared_ptr executor; std::thread thread; + std::atomic_bool thread_initialized; + + /// Constructor for the wrapper. + /// This is necessary as atomic variables don't have copy/move operators + /// implemented so this structure is not copyable/movable by default + explicit DedicatedExecutorWrapper(std::shared_ptr exec) + : executor(exec), + thread_initialized(false) + { + } }; public: @@ -59,15 +69,19 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager void add_node_to_executor(uint64_t node_id) override { - DedicatedExecutorWrapper executor_wrapper; auto exec = std::make_shared(); exec->add_node(node_wrappers_[node_id].get_node_base_interface()); - executor_wrapper.executor = exec; - executor_wrapper.thread = std::thread( - [exec]() { + + // Emplace rather than std::move since move operations are deleted for atomics + auto result = dedicated_executor_wrappers_.emplace(std::make_pair(node_id, exec)); + DedicatedExecutorWrapper & wrapper = result.first->second; + wrapper.executor = exec; + auto & thread_initialized = wrapper.thread_initialized; + wrapper.thread = std::thread( + [exec, &thread_initialized]() { + thread_initialized = true; exec->spin(); }); - dedicated_executor_wrappers_[node_id] = std::move(executor_wrapper); } /// Remove component node from executor model, it's invoked in on_unload_node() /** @@ -90,15 +104,21 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager */ void cancel_executor(DedicatedExecutorWrapper & executor_wrapper) { - // We can't immediately call the cancel() API on an executor because if it is not - // already spinning, this operation will have no effect. - // We rely on the assumption that this class creates executors and then immediately makes them - // spin in a separate thread, i.e. the time gap between when the executor is created and when - // it starts to spin is small (although it's not negligible). - - while (!executor_wrapper.executor->is_spinning()) { - // This is an arbitrarily small delay to avoid busy looping - rclcpp::sleep_for(std::chrono::milliseconds(1)); + // Verify that the executor thread has begun spinning. + // If it has not, then wait until the thread starts to ensure + // that cancel() will fully stop the execution + // + // This prevents a previous race condition that occurs between the + // creation of the executor spin thread and cancelling an executor + + if (!executor_wrapper.thread_initialized) { + auto context = this->get_node_base_interface()->get_context(); + + // Guarantee that either the executor is spinning or we are shutting down. + while (!executor_wrapper.executor->is_spinning() && rclcpp::ok(context)) { + // This is an arbitrarily small delay to avoid busy looping + rclcpp::sleep_for(std::chrono::milliseconds(1)); + } } // After the while loop we are sure that the executor is now spinning, so diff --git a/rclcpp_components/package.xml b/rclcpp_components/package.xml index 18275306ff..de1b88e242 100644 --- a/rclcpp_components/package.xml +++ b/rclcpp_components/package.xml @@ -2,12 +2,16 @@ rclcpp_components - 16.2.0 + 18.0.0 Package containing tools for dynamically loadable components + Ivan Paunovic - Jacob Perron + Michel Hidalgo William Woodall + Apache License 2.0 + + Jacob Perron Michael Carroll ament_cmake_ros diff --git a/rclcpp_components/src/node_main.cpp.in b/rclcpp_components/src/node_main.cpp.in index 0ca5eb8c61..71754d1f82 100644 --- a/rclcpp_components/src/node_main.cpp.in +++ b/rclcpp_components/src/node_main.cpp.in @@ -30,14 +30,13 @@ int main(int argc, char * argv[]) rclcpp::executors::@executor@ exec; rclcpp::NodeOptions options; options.arguments(args); - std::vector loaders; std::vector node_wrappers; std::string library_name = "@library_name@"; std::string class_name = "rclcpp_components::NodeFactoryTemplate<@component@>"; RCLCPP_DEBUG(logger, "Load library %s", library_name.c_str()); - auto loader = new class_loader::ClassLoader(library_name); + auto loader = std::make_unique(library_name); auto classes = loader->getAvailableClasses(); for (const auto & clazz : classes) { std::string name = clazz.c_str(); @@ -59,8 +58,6 @@ int main(int argc, char * argv[]) exec.add_node(node); } } - loaders.push_back(loader); - exec.spin(); diff --git a/rclcpp_lifecycle/CHANGELOG.rst b/rclcpp_lifecycle/CHANGELOG.rst index 420252b66a..0285505488 100644 --- a/rclcpp_lifecycle/CHANGELOG.rst +++ b/rclcpp_lifecycle/CHANGELOG.rst @@ -3,6 +3,32 @@ Changelog for package rclcpp_lifecycle ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +18.0.0 (2022-12-29) +------------------- +* Implement Unified Node Interface (NodeInterfaces class) (`#2041 `_) +* Add clock type to node_options (`#1982 `_) +* Update maintainers (`#2043 `_) +* Contributors: Audrow Nash, Jeffery Hsu, methylDragon + +17.1.0 (2022-11-02) +------------------- +* LifecycleNode on_configure doc fix. (`#2034 `_) +* Bugfix 20210810 get current state (`#1756 `_) +* Make lifecycle impl get_current_state() const. (`#2031 `_) +* Cleanup the lifecycle implementation (`#2027 `_) +* Cleanup the rclcpp_lifecycle dependencies. (`#2021 `_) +* Contributors: Chris Lalancette, Tomoya Fujita + +17.0.0 (2022-09-13) +------------------- +* Revert "Revert "Add a create_timer method to Node and `LifecycleNode` classes (`#1975 `_)" (`#2009 `_) (`#2010 `_) +* Revert "Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 `_)" (`#2009 `_) +* Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 `_) +* Support pre-set and post-set parameter callbacks in addition to on-set-parameter-callback. (`#1947 `_) +* Make create_service accept rclcpp::QoS (`#1969 `_) +* Make create_client accept rclcpp::QoS (`#1964 `_) +* Contributors: Andrew Symington, Deepanshu Bansal, Ivan Santiago Paunovic, Shane Loretz + 16.2.0 (2022-05-03) ------------------- diff --git a/rclcpp_lifecycle/CMakeLists.txt b/rclcpp_lifecycle/CMakeLists.txt index a823d44a68..b3461a7333 100644 --- a/rclcpp_lifecycle/CMakeLists.txt +++ b/rclcpp_lifecycle/CMakeLists.txt @@ -11,14 +11,18 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() find_package(ament_cmake_ros REQUIRED) +find_package(lifecycle_msgs REQUIRED) +find_package(rcl REQUIRED) find_package(rclcpp REQUIRED) +find_package(rcl_interfaces REQUIRED) find_package(rcl_lifecycle REQUIRED) +find_package(rcutils REQUIRED) find_package(rosidl_typesupport_cpp REQUIRED) -find_package(lifecycle_msgs REQUIRED) ### CPP High level library add_library(rclcpp_lifecycle src/lifecycle_node.cpp + src/lifecycle_node_interface_impl.cpp src/managed_entity.cpp src/node_interfaces/lifecycle_node_interface.cpp src/state.cpp @@ -28,12 +32,14 @@ target_include_directories(${PROJECT_NAME} PUBLIC "$" "$") -# specific order: dependents before dependencies -ament_target_dependencies(rclcpp_lifecycle - "rclcpp" - "rcl_lifecycle" - "lifecycle_msgs" - "rosidl_typesupport_cpp" +target_link_libraries(${PROJECT_NAME} + ${lifecycle_msgs_TARGETS} + rcl::rcl + rclcpp::rclcpp + ${rcl_interfaces_TARGETS} + rcl_lifecycle::rcl_lifecycle + rcutils::rcutils + rosidl_typesupport_cpp::rosidl_typesupport_cpp ) # Causes the visibility macros to use dllexport rather than dllimport, @@ -46,6 +52,9 @@ install(TARGETS LIBRARY DESTINATION lib RUNTIME DESTINATION bin) +install(DIRECTORY include/ + DESTINATION include/${PROJECT_NAME}) + if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) # Give cppcheck hints about macro definitions coming from outside this package @@ -58,15 +67,13 @@ if(BUILD_TESTING) benchmark_lifecycle_client test/benchmark/benchmark_lifecycle_client.cpp) if(TARGET benchmark_lifecycle_client) - target_link_libraries(benchmark_lifecycle_client ${PROJECT_NAME}) - ament_target_dependencies(benchmark_lifecycle_client rclcpp) + target_link_libraries(benchmark_lifecycle_client ${PROJECT_NAME} rclcpp::rclcpp) endif() add_performance_test( benchmark_lifecycle_node test/benchmark/benchmark_lifecycle_node.cpp) if(TARGET benchmark_lifecycle_node) - target_link_libraries(benchmark_lifecycle_node ${PROJECT_NAME}) - ament_target_dependencies(benchmark_lifecycle_node rclcpp) + target_link_libraries(benchmark_lifecycle_node ${PROJECT_NAME} rclcpp::rclcpp) endif() add_performance_test( benchmark_state @@ -83,72 +90,57 @@ if(BUILD_TESTING) ament_add_gtest(test_lifecycle_node test/test_lifecycle_node.cpp TIMEOUT 120) if(TARGET test_lifecycle_node) - ament_target_dependencies(test_lifecycle_node - "rcl_lifecycle" - "rclcpp" - "rcutils" - ) - target_link_libraries(test_lifecycle_node ${PROJECT_NAME} mimick) + target_link_libraries(test_lifecycle_node ${PROJECT_NAME} mimick rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp rcutils::rcutils) endif() ament_add_gtest(test_lifecycle_publisher test/test_lifecycle_publisher.cpp) if(TARGET test_lifecycle_publisher) - ament_target_dependencies(test_lifecycle_publisher - "rcl_lifecycle" - "rclcpp" - "test_msgs" - ) - target_link_libraries(test_lifecycle_publisher ${PROJECT_NAME}) + target_link_libraries(test_lifecycle_publisher ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp ${test_msgs_TARGETS}) endif() ament_add_gtest(test_lifecycle_service_client test/test_lifecycle_service_client.cpp TIMEOUT 120) if(TARGET test_lifecycle_service_client) - ament_target_dependencies(test_lifecycle_service_client - "rcl_lifecycle" - "rclcpp" - "rcpputils" - "rcutils" - ) - target_link_libraries(test_lifecycle_service_client ${PROJECT_NAME} mimick) + target_link_libraries(test_lifecycle_service_client + ${PROJECT_NAME} + mimick + rcl_lifecycle::rcl_lifecycle + rclcpp::rclcpp + rcpputils::rcpputils + rcutils::rcutils) + endif() + ament_add_gtest(test_client test/test_client.cpp TIMEOUT 120) + if(TARGET test_client) + target_link_libraries(test_client + ${PROJECT_NAME} + mimick + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp) + endif() + ament_add_gtest(test_service test/test_service.cpp TIMEOUT 120) + if(TARGET test_service) + target_link_libraries(test_service + ${PROJECT_NAME} + mimick + ${test_msgs_TARGETS} + rclcpp::rclcpp) endif() ament_add_gtest(test_state_machine_info test/test_state_machine_info.cpp) if(TARGET test_state_machine_info) - ament_target_dependencies(test_state_machine_info - "rcl_lifecycle" - "rclcpp" - ) - target_link_libraries(test_state_machine_info ${PROJECT_NAME}) + target_link_libraries(test_state_machine_info ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp) endif() ament_add_gtest(test_register_custom_callbacks test/test_register_custom_callbacks.cpp) if(TARGET test_register_custom_callbacks) - ament_target_dependencies(test_register_custom_callbacks - "rcl_lifecycle" - "rclcpp" - ) - target_link_libraries(test_register_custom_callbacks ${PROJECT_NAME}) + target_link_libraries(test_register_custom_callbacks ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp) endif() ament_add_gtest(test_callback_exceptions test/test_callback_exceptions.cpp) if(TARGET test_callback_exceptions) - ament_target_dependencies(test_callback_exceptions - "rcl_lifecycle" - "rclcpp" - ) - target_link_libraries(test_callback_exceptions ${PROJECT_NAME}) + target_link_libraries(test_callback_exceptions ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp) endif() ament_add_gtest(test_state_wrapper test/test_state_wrapper.cpp) if(TARGET test_state_wrapper) - ament_target_dependencies(test_state_wrapper - "rcl_lifecycle" - "rclcpp" - ) - target_link_libraries(test_state_wrapper ${PROJECT_NAME}) + target_link_libraries(test_state_wrapper ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp) endif() ament_add_gtest(test_transition_wrapper test/test_transition_wrapper.cpp) if(TARGET test_transition_wrapper) - ament_target_dependencies(test_transition_wrapper - "rcl_lifecycle" - "rclcpp" - "rcutils" - ) - target_link_libraries(test_transition_wrapper ${PROJECT_NAME} mimick) + target_link_libraries(test_transition_wrapper ${PROJECT_NAME} mimick rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp rcutils::rcutils) target_compile_definitions(test_transition_wrapper PUBLIC RCUTILS_ENABLE_FAULT_INJECTION ) @@ -162,11 +154,7 @@ ament_export_libraries(${PROJECT_NAME}) # Export modern CMake targets ament_export_targets(${PROJECT_NAME}) -# specific order: dependents before dependencies -ament_export_dependencies(rclcpp) -ament_export_dependencies(rcl_lifecycle) -ament_export_dependencies(lifecycle_msgs) -ament_package() +# Export dependencies +ament_export_dependencies(lifecycle_msgs rcl rclcpp rcl_interfaces rcl_lifecycle rcutils rosidl_typesupport_cpp) -install(DIRECTORY include/ - DESTINATION include/${PROJECT_NAME}) +ament_package() diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 6048d0d691..50d4717ec3 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -36,6 +36,8 @@ #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_ #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_ +#include +#include #include #include #include @@ -49,13 +51,11 @@ #include "rcl_interfaces/msg/list_parameters_result.hpp" #include "rcl_interfaces/msg/parameter_descriptor.hpp" -#include "rcl_interfaces/msg/parameter_event.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" #include "rclcpp/callback_group.hpp" #include "rclcpp/client.hpp" #include "rclcpp/clock.hpp" -#include "rclcpp/context.hpp" #include "rclcpp/event.hpp" #include "rclcpp/generic_publisher.hpp" #include "rclcpp/generic_subscription.hpp" @@ -83,6 +83,8 @@ #include "rclcpp/time.hpp" #include "rclcpp/timer.hpp" +#include "rmw/types.h" + #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" #include "rclcpp_lifecycle/state.hpp" @@ -137,7 +139,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, const rclcpp::NodeOptions & options = rclcpp::NodeOptions(), bool enable_communication_interface = true); - /// Create a node based on the node name and a rclcpp::Context. + /// Create a node based on the node name /** * \param[in] node_name Name of the node. * \param[in] namespace_ Namespace of the node. @@ -242,7 +244,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, ) ); - /// Create a timer. + /// Create a timer that uses the wall clock to drive the callback. /** * \param[in] period Time interval between triggers of the callback. * \param[in] callback User-defined callback function. @@ -255,15 +257,58 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr); + /// Create a timer that uses the node clock to drive the callback. + /** + * \param[in] period Time interval between triggers of the callback. + * \param[in] callback User-defined callback function. + * \param[in] group Callback group to execute this timer's callback in. + */ + template + typename rclcpp::GenericTimer::SharedPtr + create_timer( + std::chrono::duration period, + CallbackT callback, + rclcpp::CallbackGroup::SharedPtr group = nullptr); + /// Create and return a Client. /** * \sa rclcpp::Node::create_client + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + typename rclcpp::Client::SharedPtr + create_client( + const std::string & service_name, + const rmw_qos_profile_t & qos_profile, + rclcpp::CallbackGroup::SharedPtr group = nullptr); + + /// Create and return a Client. + /** + * \param[in] service_name The name on which the service is accessible. + * \param[in] qos Quality of service profile for client. + * \param[in] group Callback group to handle the reply to service calls. + * \return Shared pointer to the created client. */ template typename rclcpp::Client::SharedPtr create_client( const std::string & service_name, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, + const rclcpp::QoS & qos = rclcpp::ServicesQoS(), + rclcpp::CallbackGroup::SharedPtr group = nullptr); + + /// Create and return a Service. + /** + * \sa rclcpp::Node::create_service + * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t + */ + template + [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] + typename rclcpp::Service::SharedPtr + create_service( + const std::string & service_name, + CallbackT && callback, + const rmw_qos_profile_t & qos_profile, rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Create and return a Service. @@ -275,7 +320,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, create_service( const std::string & service_name, CallbackT && callback, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, + const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Create and return a GenericPublisher. @@ -508,10 +553,32 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const; + using PreSetParametersCallbackHandle = + rclcpp::node_interfaces::PreSetParametersCallbackHandle; + using PreSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType; + using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle; - using OnParametersSetCallbackType = - rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType; + using OnSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType; + using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] = + OnSetParametersCallbackType; + + using PostSetParametersCallbackHandle = + rclcpp::node_interfaces::PostSetParametersCallbackHandle; + using PostSetParametersCallbackType = + rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType; + + /// Add a callback that gets triggered before parameters are validated. + /** + * \sa rclcpp::Node::add_pre_set_parameters_callback + */ + RCLCPP_LIFECYCLE_PUBLIC + RCUTILS_WARN_UNUSED + rclcpp_lifecycle::LifecycleNode::PreSetParametersCallbackHandle::SharedPtr + add_pre_set_parameters_callback( + rclcpp_lifecycle::LifecycleNode::PreSetParametersCallbackType callback); /// Add a callback for when parameters are being set. /** @@ -521,7 +588,26 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, RCUTILS_WARN_UNUSED rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback( - rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback); + rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackType callback); + + /// Add a callback that gets triggered after parameters are set successfully. + /** + * \sa rclcpp::Node::add_post_set_parameters_callback + */ + RCLCPP_LIFECYCLE_PUBLIC + RCUTILS_WARN_UNUSED + rclcpp_lifecycle::LifecycleNode::PostSetParametersCallbackHandle::SharedPtr + add_post_set_parameters_callback( + rclcpp_lifecycle::LifecycleNode::PostSetParametersCallbackType callback); + + /// Remove a callback registered with `add_pre_set_parameters_callback`. + /** + * \sa rclcpp::Node::remove_pre_set_parameters_callback + */ + RCLCPP_LIFECYCLE_PUBLIC + void + remove_pre_set_parameters_callback( + const rclcpp_lifecycle::LifecycleNode::PreSetParametersCallbackHandle * const handler); /// Remove a callback registered with `add_on_set_parameters_callback`. /** @@ -532,6 +618,15 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, remove_on_set_parameters_callback( const rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle * const handler); + /// Remove a callback registered with `add_post_set_parameters_callback`. + /** + * \sa rclcpp::Node::remove_post_set_parameters_callback + */ + RCLCPP_LIFECYCLE_PUBLIC + void + remove_post_set_parameters_callback( + const rclcpp_lifecycle::LifecycleNode::PostSetParametersCallbackHandle * const handler); + /// Return a vector of existing node names (string). /** * \sa rclcpp::Node::get_node_names @@ -744,7 +839,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, */ RCLCPP_LIFECYCLE_PUBLIC const State & - get_current_state(); + get_current_state() const; /// Return a list with the available states. /** @@ -752,7 +847,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, */ RCLCPP_LIFECYCLE_PUBLIC std::vector - get_available_states(); + get_available_states() const; /// Return a list with the current available transitions. /** @@ -760,7 +855,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, */ RCLCPP_LIFECYCLE_PUBLIC std::vector - get_available_transitions(); + get_available_transitions() const; /// Return a list with all the transitions. /** @@ -768,7 +863,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, */ RCLCPP_LIFECYCLE_PUBLIC std::vector - get_transition_graph(); + get_transition_graph() const; /// Trigger the specified transition. /* diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index 22fd7f9c08..5ffc8a5f1b 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -15,28 +15,35 @@ #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_ #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_ +#include +#include +#include #include #include #include #include #include -#include "rclcpp/contexts/default_context.hpp" +#include "rcl_interfaces/msg/parameter_descriptor.hpp" + +#include "rclcpp/callback_group.hpp" +#include "rclcpp/create_client.hpp" #include "rclcpp/create_generic_publisher.hpp" #include "rclcpp/create_generic_subscription.hpp" #include "rclcpp/create_publisher.hpp" #include "rclcpp/create_service.hpp" #include "rclcpp/create_subscription.hpp" -#include "rclcpp/event.hpp" -#include "rclcpp/experimental/intra_process_manager.hpp" #include "rclcpp/parameter.hpp" +#include "rclcpp/publisher_options.hpp" +#include "rclcpp/qos.hpp" #include "rclcpp/subscription_options.hpp" #include "rclcpp/type_support_decl.hpp" -#include "lifecycle_publisher.hpp" -#include "rclcpp_lifecycle/visibility_control.h" +#include "rmw/types.h" #include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "rclcpp_lifecycle/lifecycle_publisher.hpp" +#include "rclcpp_lifecycle/visibility_control.h" namespace rclcpp_lifecycle { @@ -89,11 +96,28 @@ LifecycleNode::create_wall_timer( CallbackT callback, rclcpp::CallbackGroup::SharedPtr group) { - auto timer = rclcpp::WallTimer::make_shared( - std::chrono::duration_cast(period), - std::move(callback), this->node_base_->get_context()); - node_timers_->add_timer(timer, group); - return timer; + return rclcpp::create_wall_timer( + period, + std::move(callback), + group, + this->node_base_.get(), + this->node_timers_.get()); +} + +template +typename rclcpp::GenericTimer::SharedPtr +LifecycleNode::create_timer( + std::chrono::duration period, + CallbackT callback, + rclcpp::CallbackGroup::SharedPtr group) +{ + return rclcpp::create_timer( + this->get_clock(), + period, + std::move(callback), + group, + this->node_base_.get(), + this->node_timers_.get()); } template @@ -103,21 +127,21 @@ LifecycleNode::create_client( const rmw_qos_profile_t & qos_profile, rclcpp::CallbackGroup::SharedPtr group) { - rcl_client_options_t options = rcl_client_get_default_options(); - options.qos = qos_profile; - - using rclcpp::Client; - using rclcpp::ClientBase; - - auto cli = Client::make_shared( - node_base_.get(), - node_graph_, - service_name, - options); + return rclcpp::create_client( + node_base_, node_graph_, node_services_, + service_name, qos_profile, group); +} - auto cli_base_ptr = std::dynamic_pointer_cast(cli); - node_services_->add_client(cli_base_ptr, group); - return cli; +template +typename rclcpp::Client::SharedPtr +LifecycleNode::create_client( + const std::string & service_name, + const rclcpp::QoS & qos, + rclcpp::CallbackGroup::SharedPtr group) +{ + return rclcpp::create_client( + node_base_, node_graph_, node_services_, + service_name, qos, group); } template @@ -133,6 +157,19 @@ LifecycleNode::create_service( service_name, std::forward(callback), qos_profile, group); } +template +typename rclcpp::Service::SharedPtr +LifecycleNode::create_service( + const std::string & service_name, + CallbackT && callback, + const rclcpp::QoS & qos, + rclcpp::CallbackGroup::SharedPtr group) +{ + return rclcpp::create_service( + node_base_, node_services_, + service_name, std::forward(callback), qos, group); +} + template std::shared_ptr LifecycleNode::create_generic_publisher( diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp index 8df08dcb41..fa7c5b0b5e 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp @@ -20,7 +20,10 @@ #include #include "rclcpp/logging.hpp" +#include "rclcpp/node_interfaces/node_base_interface.hpp" #include "rclcpp/publisher.hpp" +#include "rclcpp/publisher_options.hpp" +#include "rclcpp/qos.hpp" #include "rclcpp_lifecycle/managed_entity.hpp" diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp index 9f2459e296..272c4def27 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp @@ -17,10 +17,9 @@ #include "lifecycle_msgs/msg/transition.hpp" -#include "rcl_lifecycle/rcl_lifecycle.h" - #include "rclcpp_lifecycle/state.hpp" #include "rclcpp_lifecycle/visibility_control.h" +#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp" namespace rclcpp_lifecycle { @@ -55,7 +54,7 @@ class LifecycleNodeInterface /// Callback function for configure transition /* - * \return true by default + * \return SUCCESS by default */ RCLCPP_LIFECYCLE_PUBLIC virtual CallbackReturn @@ -63,7 +62,7 @@ class LifecycleNodeInterface /// Callback function for cleanup transition /* - * \return true by default + * \return SUCCESS by default */ RCLCPP_LIFECYCLE_PUBLIC virtual CallbackReturn @@ -71,7 +70,7 @@ class LifecycleNodeInterface /// Callback function for shutdown transition /* - * \return true by default + * \return SUCCESS by default */ RCLCPP_LIFECYCLE_PUBLIC virtual CallbackReturn @@ -79,7 +78,7 @@ class LifecycleNodeInterface /// Callback function for activate transition /* - * \return true by default + * \return SUCCESS by default */ RCLCPP_LIFECYCLE_PUBLIC virtual CallbackReturn @@ -87,7 +86,7 @@ class LifecycleNodeInterface /// Callback function for deactivate transition /* - * \return true by default + * \return SUCCESS by default */ RCLCPP_LIFECYCLE_PUBLIC virtual CallbackReturn @@ -95,7 +94,7 @@ class LifecycleNodeInterface /// Callback function for errorneous transition /* - * \return false by default + * \return SUCCESS by default */ RCLCPP_LIFECYCLE_PUBLIC virtual CallbackReturn @@ -108,4 +107,8 @@ class LifecycleNodeInterface } // namespace node_interfaces } // namespace rclcpp_lifecycle + +RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT( + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface, lifecycle_node) + #endif // RCLCPP_LIFECYCLE__NODE_INTERFACES__LIFECYCLE_NODE_INTERFACE_HPP_ diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/state.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/state.hpp index a0ac997ff3..62e1c51fb3 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/state.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/state.hpp @@ -15,9 +15,11 @@ #ifndef RCLCPP_LIFECYCLE__STATE_HPP_ #define RCLCPP_LIFECYCLE__STATE_HPP_ +#include #include #include "rcl_lifecycle/data_types.h" + #include "rclcpp_lifecycle/visibility_control.h" #include "rcutils/allocator.h" @@ -91,6 +93,7 @@ class State bool owns_rcl_state_handle_; + mutable std::recursive_mutex state_handle_mutex_; rcl_lifecycle_state_t * state_handle_; }; diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/transition.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/transition.hpp index 874be69aa6..4093579e04 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/transition.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/transition.hpp @@ -18,6 +18,7 @@ #include #include "rcl_lifecycle/data_types.h" + #include "rclcpp_lifecycle/state.hpp" #include "rclcpp_lifecycle/visibility_control.h" diff --git a/rclcpp_lifecycle/package.xml b/rclcpp_lifecycle/package.xml index 3ff98f3069..092105238b 100644 --- a/rclcpp_lifecycle/package.xml +++ b/rclcpp_lifecycle/package.xml @@ -2,35 +2,44 @@ rclcpp_lifecycle - 16.2.0 + 18.0.0 Package containing a prototype for lifecycle implementation + Ivan Paunovic - Jacob Perron + Michel Hidalgo William Woodall + Apache License 2.0 + + Jacob Perron Karsten Knese ament_cmake_ros lifecycle_msgs + rcl rclcpp + rcl_interfaces rcl_lifecycle + rcutils + rmw rosidl_typesupport_cpp lifecycle_msgs + rcl rclcpp + rcl_interfaces rcl_lifecycle + rcutils + rmw rosidl_typesupport_cpp - rmw - ament_cmake_gtest ament_lint_auto ament_lint_common mimick_vendor performance_test_fixture rcpputils - rcutils test_msgs diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index 06378b594b..723c7bc8c1 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -14,15 +14,22 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" -#include +#include +#include #include #include -#include +#include +#include #include +#include #include "lifecycle_msgs/msg/state.hpp" #include "lifecycle_msgs/msg/transition.hpp" +#include "rcl_interfaces/msg/list_parameters_result.hpp" +#include "rcl_interfaces/msg/parameter_descriptor.hpp" +#include "rcl_interfaces/msg/set_parameters_result.hpp" + #include "rclcpp/exceptions.hpp" #include "rclcpp/graph_listener.hpp" #include "rclcpp/logger.hpp" @@ -78,7 +85,8 @@ LifecycleNode::LifecycleNode( node_topics_, node_graph_, node_services_, - node_logging_ + node_logging_, + options.clock_type() )), node_parameters_(new rclcpp::node_interfaces::NodeParameters( node_base_, @@ -283,12 +291,31 @@ LifecycleNode::list_parameters( return node_parameters_->list_parameters(prefixes, depth); } +rclcpp::Node::PreSetParametersCallbackHandle::SharedPtr +LifecycleNode::add_pre_set_parameters_callback(PreSetParametersCallbackType callback) +{ + return node_parameters_->add_pre_set_parameters_callback(callback); +} + rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr -LifecycleNode::add_on_set_parameters_callback(OnParametersSetCallbackType callback) +LifecycleNode::add_on_set_parameters_callback(OnSetParametersCallbackType callback) { return node_parameters_->add_on_set_parameters_callback(callback); } +rclcpp::Node::PostSetParametersCallbackHandle::SharedPtr +LifecycleNode::add_post_set_parameters_callback(PostSetParametersCallbackType callback) +{ + return node_parameters_->add_post_set_parameters_callback(callback); +} + +void +LifecycleNode::remove_pre_set_parameters_callback( + const PreSetParametersCallbackHandle * const callback) +{ + node_parameters_->remove_pre_set_parameters_callback(callback); +} + void LifecycleNode::remove_on_set_parameters_callback( const OnSetParametersCallbackHandle * const callback) @@ -296,6 +323,13 @@ LifecycleNode::remove_on_set_parameters_callback( node_parameters_->remove_on_set_parameters_callback(callback); } +void +LifecycleNode::remove_post_set_parameters_callback( + const PostSetParametersCallbackHandle * const callback) +{ + node_parameters_->remove_post_set_parameters_callback(callback); +} + std::vector LifecycleNode::get_node_names() const { @@ -502,25 +536,25 @@ LifecycleNode::register_on_error( } const State & -LifecycleNode::get_current_state() +LifecycleNode::get_current_state() const { return impl_->get_current_state(); } std::vector -LifecycleNode::get_available_states() +LifecycleNode::get_available_states() const { return impl_->get_available_states(); } std::vector -LifecycleNode::get_available_transitions() +LifecycleNode::get_available_transitions() const { return impl_->get_available_transitions(); } std::vector -LifecycleNode::get_transition_graph() +LifecycleNode::get_transition_graph() const { return impl_->get_transition_graph(); } diff --git a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.cpp b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.cpp new file mode 100644 index 0000000000..5c5f7797e1 --- /dev/null +++ b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.cpp @@ -0,0 +1,584 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include +#include +#include + +#include "lifecycle_msgs/msg/transition_description.hpp" +#include "lifecycle_msgs/msg/transition_event.h" // for getting the c-typesupport +#include "lifecycle_msgs/msg/transition_event.hpp" +#include "lifecycle_msgs/srv/change_state.hpp" +#include "lifecycle_msgs/srv/get_state.hpp" +#include "lifecycle_msgs/srv/get_available_states.hpp" +#include "lifecycle_msgs/srv/get_available_transitions.hpp" + +#include "rclcpp/node_interfaces/node_base_interface.hpp" +#include "rclcpp/node_interfaces/node_services_interface.hpp" + +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" + +#include "rcl/error_handling.h" +#include "rcl/node.h" + +#include "rcl_lifecycle/rcl_lifecycle.h" +#include "rcl_lifecycle/transition_map.h" + +#include "rcutils/logging_macros.h" + +#include "rmw/types.h" + +#include "lifecycle_node_interface_impl.hpp" + +namespace rclcpp_lifecycle +{ + +LifecycleNode::LifecycleNodeInterfaceImpl::LifecycleNodeInterfaceImpl( + std::shared_ptr node_base_interface, + std::shared_ptr node_services_interface) +: node_base_interface_(node_base_interface), + node_services_interface_(node_services_interface) +{ +} + +LifecycleNode::LifecycleNodeInterfaceImpl::~LifecycleNodeInterfaceImpl() +{ + rcl_node_t * node_handle = node_base_interface_->get_rcl_node_handle(); + rcl_ret_t ret; + { + std::lock_guard lock(state_machine_mutex_); + ret = rcl_lifecycle_state_machine_fini(&state_machine_, node_handle); + } + if (ret != RCL_RET_OK) { + RCUTILS_LOG_FATAL_NAMED( + "rclcpp_lifecycle", + "failed to destroy rcl_state_machine"); + } +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::init(bool enable_communication_interface) +{ + rcl_node_t * node_handle = node_base_interface_->get_rcl_node_handle(); + const rcl_node_options_t * node_options = + rcl_node_get_options(node_base_interface_->get_rcl_node_handle()); + auto state_machine_options = rcl_lifecycle_get_default_state_machine_options(); + state_machine_options.enable_com_interface = enable_communication_interface; + state_machine_options.allocator = node_options->allocator; + + // The call to initialize the state machine takes + // currently five different typesupports for all publishers/services + // created within the RCL_LIFECYCLE structure. + // The publisher takes a C-Typesupport since the publishing (i.e. creating + // the message) is done fully in RCL. + // Services are handled in C++, so that it needs a C++ typesupport structure. + std::lock_guard lock(state_machine_mutex_); + state_machine_ = rcl_lifecycle_get_zero_initialized_state_machine(); + rcl_ret_t ret = rcl_lifecycle_state_machine_init( + &state_machine_, + node_handle, + ROSIDL_GET_MSG_TYPE_SUPPORT(lifecycle_msgs, msg, TransitionEvent), + rosidl_typesupport_cpp::get_service_type_support_handle(), + rosidl_typesupport_cpp::get_service_type_support_handle(), + rosidl_typesupport_cpp::get_service_type_support_handle(), + rosidl_typesupport_cpp::get_service_type_support_handle(), + rosidl_typesupport_cpp::get_service_type_support_handle(), + &state_machine_options); + if (ret != RCL_RET_OK) { + throw std::runtime_error( + std::string("Couldn't initialize state machine for node ") + + node_base_interface_->get_name()); + } + + current_state_ = State(state_machine_.current_state); + + if (enable_communication_interface) { + { // change_state + auto cb = std::bind( + &LifecycleNode::LifecycleNodeInterfaceImpl::on_change_state, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); + rclcpp::AnyServiceCallback any_cb; + any_cb.set(std::move(cb)); + + srv_change_state_ = std::make_shared>( + node_base_interface_->get_shared_rcl_node_handle(), + &state_machine_.com_interface.srv_change_state, + any_cb); + node_services_interface_->add_service( + std::dynamic_pointer_cast(srv_change_state_), + nullptr); + } + + { // get_state + auto cb = std::bind( + &LifecycleNode::LifecycleNodeInterfaceImpl::on_get_state, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); + rclcpp::AnyServiceCallback any_cb; + any_cb.set(std::move(cb)); + + srv_get_state_ = std::make_shared>( + node_base_interface_->get_shared_rcl_node_handle(), + &state_machine_.com_interface.srv_get_state, + any_cb); + node_services_interface_->add_service( + std::dynamic_pointer_cast(srv_get_state_), + nullptr); + } + + { // get_available_states + auto cb = std::bind( + &LifecycleNode::LifecycleNodeInterfaceImpl::on_get_available_states, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); + rclcpp::AnyServiceCallback any_cb; + any_cb.set(std::move(cb)); + + srv_get_available_states_ = std::make_shared>( + node_base_interface_->get_shared_rcl_node_handle(), + &state_machine_.com_interface.srv_get_available_states, + any_cb); + node_services_interface_->add_service( + std::dynamic_pointer_cast(srv_get_available_states_), + nullptr); + } + + { // get_available_transitions + auto cb = std::bind( + &LifecycleNode::LifecycleNodeInterfaceImpl::on_get_available_transitions, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); + rclcpp::AnyServiceCallback any_cb; + any_cb.set(std::move(cb)); + + srv_get_available_transitions_ = + std::make_shared>( + node_base_interface_->get_shared_rcl_node_handle(), + &state_machine_.com_interface.srv_get_available_transitions, + any_cb); + node_services_interface_->add_service( + std::dynamic_pointer_cast(srv_get_available_transitions_), + nullptr); + } + + { // get_transition_graph + auto cb = std::bind( + &LifecycleNode::LifecycleNodeInterfaceImpl::on_get_transition_graph, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); + rclcpp::AnyServiceCallback any_cb; + any_cb.set(std::move(cb)); + + srv_get_transition_graph_ = + std::make_shared>( + node_base_interface_->get_shared_rcl_node_handle(), + &state_machine_.com_interface.srv_get_transition_graph, + any_cb); + node_services_interface_->add_service( + std::dynamic_pointer_cast(srv_get_transition_graph_), + nullptr); + } + } +} + +bool +LifecycleNode::LifecycleNodeInterfaceImpl::register_callback( + std::uint8_t lifecycle_transition, + std::function & cb) +{ + cb_map_[lifecycle_transition] = cb; + return true; +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_change_state( + const std::shared_ptr header, + const std::shared_ptr req, + std::shared_ptr resp) +{ + (void)header; + std::uint8_t transition_id; + { + std::lock_guard lock(state_machine_mutex_); + if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { + throw std::runtime_error("Can't get state. State machine is not initialized."); + } + + transition_id = req->transition.id; + // if there's a label attached to the request, + // we check the transition attached to this label. + // we further can't compare the id of the looked up transition + // because ros2 service call defaults all intergers to zero. + // that means if we call ros2 service call ... {transition: {label: shutdown}} + // the id of the request is 0 (zero) whereas the id from the lookup up transition + // can be different. + // the result of this is that the label takes presedence of the id. + if (req->transition.label.size() != 0) { + auto rcl_transition = rcl_lifecycle_get_transition_by_label( + state_machine_.current_state, req->transition.label.c_str()); + if (rcl_transition == nullptr) { + resp->success = false; + return; + } + transition_id = static_cast(rcl_transition->id); + } + } + + node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code; + auto ret = change_state(transition_id, cb_return_code); + (void) ret; + // TODO(karsten1987): Lifecycle msgs have to be extended to keep both returns + // 1. return is the actual transition + // 2. return is whether an error occurred or not + resp->success = + (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS); +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_get_state( + const std::shared_ptr header, + const std::shared_ptr req, + std::shared_ptr resp) const +{ + (void)header; + (void)req; + std::lock_guard lock(state_machine_mutex_); + if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { + throw std::runtime_error( + "Can't get state. State machine is not initialized."); + } + resp->current_state.id = static_cast(state_machine_.current_state->id); + resp->current_state.label = state_machine_.current_state->label; +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_get_available_states( + const std::shared_ptr header, + const std::shared_ptr req, + std::shared_ptr resp) const +{ + (void)header; + (void)req; + std::lock_guard lock(state_machine_mutex_); + if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { + throw std::runtime_error( + "Can't get available states. State machine is not initialized."); + } + + resp->available_states.resize(state_machine_.transition_map.states_size); + for (unsigned int i = 0; i < state_machine_.transition_map.states_size; ++i) { + resp->available_states[i].id = + static_cast(state_machine_.transition_map.states[i].id); + resp->available_states[i].label = + static_cast(state_machine_.transition_map.states[i].label); + } +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_get_available_transitions( + const std::shared_ptr header, + const std::shared_ptr req, + std::shared_ptr resp) const +{ + (void)header; + (void)req; + std::lock_guard lock(state_machine_mutex_); + if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { + throw std::runtime_error( + "Can't get available transitions. State machine is not initialized."); + } + + resp->available_transitions.resize(state_machine_.current_state->valid_transition_size); + for (unsigned int i = 0; i < state_machine_.current_state->valid_transition_size; ++i) { + lifecycle_msgs::msg::TransitionDescription & trans_desc = resp->available_transitions[i]; + + auto rcl_transition = state_machine_.current_state->valid_transitions[i]; + trans_desc.transition.id = static_cast(rcl_transition.id); + trans_desc.transition.label = rcl_transition.label; + trans_desc.start_state.id = static_cast(rcl_transition.start->id); + trans_desc.start_state.label = rcl_transition.start->label; + trans_desc.goal_state.id = static_cast(rcl_transition.goal->id); + trans_desc.goal_state.label = rcl_transition.goal->label; + } +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_get_transition_graph( + const std::shared_ptr header, + const std::shared_ptr req, + std::shared_ptr resp) const +{ + (void)header; + (void)req; + std::lock_guard lock(state_machine_mutex_); + if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { + throw std::runtime_error( + "Can't get available transitions. State machine is not initialized."); + } + + resp->available_transitions.resize(state_machine_.transition_map.transitions_size); + for (unsigned int i = 0; i < state_machine_.transition_map.transitions_size; ++i) { + lifecycle_msgs::msg::TransitionDescription & trans_desc = resp->available_transitions[i]; + + auto rcl_transition = state_machine_.transition_map.transitions[i]; + trans_desc.transition.id = static_cast(rcl_transition.id); + trans_desc.transition.label = rcl_transition.label; + trans_desc.start_state.id = static_cast(rcl_transition.start->id); + trans_desc.start_state.label = rcl_transition.start->label; + trans_desc.goal_state.id = static_cast(rcl_transition.goal->id); + trans_desc.goal_state.label = rcl_transition.goal->label; + } +} + +const State & +LifecycleNode::LifecycleNodeInterfaceImpl::get_current_state() const +{ + return current_state_; +} + +std::vector +LifecycleNode::LifecycleNodeInterfaceImpl::get_available_states() const +{ + std::vector states; + std::lock_guard lock(state_machine_mutex_); + states.reserve(state_machine_.transition_map.states_size); + + for (unsigned int i = 0; i < state_machine_.transition_map.states_size; ++i) { + states.emplace_back(&state_machine_.transition_map.states[i]); + } + return states; +} + +std::vector +LifecycleNode::LifecycleNodeInterfaceImpl::get_available_transitions() const +{ + std::vector transitions; + std::lock_guard lock(state_machine_mutex_); + transitions.reserve(state_machine_.current_state->valid_transition_size); + + for (unsigned int i = 0; i < state_machine_.current_state->valid_transition_size; ++i) { + transitions.emplace_back(&state_machine_.current_state->valid_transitions[i]); + } + return transitions; +} + +std::vector +LifecycleNode::LifecycleNodeInterfaceImpl::get_transition_graph() const +{ + std::vector transitions; + std::lock_guard lock(state_machine_mutex_); + transitions.reserve(state_machine_.transition_map.transitions_size); + + for (unsigned int i = 0; i < state_machine_.transition_map.transitions_size; ++i) { + transitions.emplace_back(&state_machine_.transition_map.transitions[i]); + } + return transitions; +} + +rcl_ret_t +LifecycleNode::LifecycleNodeInterfaceImpl::change_state( + std::uint8_t transition_id, + node_interfaces::LifecycleNodeInterface::CallbackReturn & cb_return_code) +{ + constexpr bool publish_update = true; + State initial_state; + unsigned int current_state_id; + + { + std::lock_guard lock(state_machine_mutex_); + if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { + RCUTILS_LOG_ERROR( + "Unable to change state for state machine for %s: %s", + node_base_interface_->get_name(), rcl_get_error_string().str); + return RCL_RET_ERROR; + } + + // keep the initial state to pass to a transition callback + initial_state = State(state_machine_.current_state); + + if ( + rcl_lifecycle_trigger_transition_by_id( + &state_machine_, transition_id, publish_update) != RCL_RET_OK) + { + RCUTILS_LOG_ERROR( + "Unable to start transition %u from current state %s: %s", + transition_id, state_machine_.current_state->label, rcl_get_error_string().str); + rcutils_reset_error(); + return RCL_RET_ERROR; + } + current_state_id = state_machine_.current_state->id; + } + + // Update the internal current_state_ + current_state_ = State(state_machine_.current_state); + + auto get_label_for_return_code = + [](node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code) -> const char *{ + auto cb_id = static_cast(cb_return_code); + if (cb_id == lifecycle_msgs::msg::Transition::TRANSITION_CALLBACK_SUCCESS) { + return rcl_lifecycle_transition_success_label; + } else if (cb_id == lifecycle_msgs::msg::Transition::TRANSITION_CALLBACK_FAILURE) { + return rcl_lifecycle_transition_failure_label; + } + return rcl_lifecycle_transition_error_label; + }; + + cb_return_code = execute_callback(current_state_id, initial_state); + auto transition_label = get_label_for_return_code(cb_return_code); + + { + std::lock_guard lock(state_machine_mutex_); + if ( + rcl_lifecycle_trigger_transition_by_label( + &state_machine_, transition_label, publish_update) != RCL_RET_OK) + { + RCUTILS_LOG_ERROR( + "Failed to finish transition %u. Current state is now: %s (%s)", + transition_id, state_machine_.current_state->label, rcl_get_error_string().str); + rcutils_reset_error(); + return RCL_RET_ERROR; + } + current_state_id = state_machine_.current_state->id; + } + + // Update the internal current_state_ + current_state_ = State(state_machine_.current_state); + + // error handling ?! + // TODO(karsten1987): iterate over possible ret value + if (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR) { + RCUTILS_LOG_WARN("Error occurred while doing error handling."); + + auto error_cb_code = execute_callback(current_state_id, initial_state); + auto error_cb_label = get_label_for_return_code(error_cb_code); + std::lock_guard lock(state_machine_mutex_); + if ( + rcl_lifecycle_trigger_transition_by_label( + &state_machine_, error_cb_label, publish_update) != RCL_RET_OK) + { + RCUTILS_LOG_ERROR("Failed to call cleanup on error state: %s", rcl_get_error_string().str); + rcutils_reset_error(); + return RCL_RET_ERROR; + } + } + + // Update the internal current_state_ + current_state_ = State(state_machine_.current_state); + + // This true holds in both cases where the actual callback + // was successful or not, since at this point we have a valid transistion + // to either a new primary state or error state + return RCL_RET_OK; +} + +node_interfaces::LifecycleNodeInterface::CallbackReturn +LifecycleNode::LifecycleNodeInterfaceImpl::execute_callback( + unsigned int cb_id, const State & previous_state) const +{ + // in case no callback was attached, we forward directly + auto cb_success = node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; + + auto it = cb_map_.find(static_cast(cb_id)); + if (it != cb_map_.end()) { + auto callback = it->second; + try { + cb_success = callback(State(previous_state)); + } catch (const std::exception & e) { + RCUTILS_LOG_ERROR("Caught exception in callback for transition %d", it->first); + RCUTILS_LOG_ERROR("Original error: %s", e.what()); + cb_success = node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; + } + } + return cb_success; +} + +const State & LifecycleNode::LifecycleNodeInterfaceImpl::trigger_transition( + const char * transition_label) +{ + node_interfaces::LifecycleNodeInterface::CallbackReturn error; + return trigger_transition(transition_label, error); +} + +const State & LifecycleNode::LifecycleNodeInterfaceImpl::trigger_transition( + const char * transition_label, + node_interfaces::LifecycleNodeInterface::CallbackReturn & cb_return_code) +{ + const rcl_lifecycle_transition_t * transition; + { + std::lock_guard lock(state_machine_mutex_); + + transition = + rcl_lifecycle_get_transition_by_label(state_machine_.current_state, transition_label); + } + if (transition) { + change_state(static_cast(transition->id), cb_return_code); + } + return get_current_state(); +} + +const State & +LifecycleNode::LifecycleNodeInterfaceImpl::trigger_transition(uint8_t transition_id) +{ + node_interfaces::LifecycleNodeInterface::CallbackReturn error; + change_state(transition_id, error); + (void) error; + return get_current_state(); +} + +const State & +LifecycleNode::LifecycleNodeInterfaceImpl::trigger_transition( + uint8_t transition_id, + node_interfaces::LifecycleNodeInterface::CallbackReturn & cb_return_code) +{ + change_state(transition_id, cb_return_code); + return get_current_state(); +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::add_managed_entity( + std::weak_ptr managed_entity) +{ + weak_managed_entities_.push_back(managed_entity); +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::add_timer_handle( + std::shared_ptr timer) +{ + weak_timers_.push_back(timer); +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_activate() const +{ + for (const auto & weak_entity : weak_managed_entities_) { + auto entity = weak_entity.lock(); + if (entity) { + entity->on_activate(); + } + } +} + +void +LifecycleNode::LifecycleNodeInterfaceImpl::on_deactivate() const +{ + for (const auto & weak_entity : weak_managed_entities_) { + auto entity = weak_entity.lock(); + if (entity) { + entity->on_deactivate(); + } + } +} + +} // namespace rclcpp_lifecycle diff --git a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp index 51de8eab07..d09f44831c 100644 --- a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp +++ b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp @@ -20,32 +20,28 @@ #include #include #include -#include #include -#include -#include "lifecycle_msgs/msg/transition_description.hpp" -#include "lifecycle_msgs/msg/transition_event.h" // for getting the c-typesupport #include "lifecycle_msgs/msg/transition_event.hpp" #include "lifecycle_msgs/srv/change_state.hpp" #include "lifecycle_msgs/srv/get_state.hpp" #include "lifecycle_msgs/srv/get_available_states.hpp" #include "lifecycle_msgs/srv/get_available_transitions.hpp" -#include "rcl/error_handling.h" - #include "rcl_lifecycle/rcl_lifecycle.h" -#include "rcl_lifecycle/transition_map.h" +#include "rclcpp/macros.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" #include "rclcpp/node_interfaces/node_services_interface.hpp" -#include "rcutils/logging_macros.h" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" + +#include "rmw/types.h" namespace rclcpp_lifecycle { -class LifecycleNode::LifecycleNodeInterfaceImpl +class LifecycleNode::LifecycleNodeInterfaceImpl final { using ChangeStateSrv = lifecycle_msgs::srv::ChangeState; using GetStateSrv = lifecycle_msgs::srv::GetState; @@ -56,489 +52,103 @@ class LifecycleNode::LifecycleNodeInterfaceImpl public: LifecycleNodeInterfaceImpl( std::shared_ptr node_base_interface, - std::shared_ptr node_services_interface) - : node_base_interface_(node_base_interface), - node_services_interface_(node_services_interface) - {} - - ~LifecycleNodeInterfaceImpl() - { - rcl_node_t * node_handle = node_base_interface_->get_rcl_node_handle(); - auto ret = rcl_lifecycle_state_machine_fini(&state_machine_, node_handle); - if (ret != RCL_RET_OK) { - RCUTILS_LOG_FATAL_NAMED( - "rclcpp_lifecycle", - "failed to destroy rcl_state_machine"); - } - } + std::shared_ptr node_services_interface); + + ~LifecycleNodeInterfaceImpl(); void - init(bool enable_communication_interface = true) - { - rcl_node_t * node_handle = node_base_interface_->get_rcl_node_handle(); - const rcl_node_options_t * node_options = - rcl_node_get_options(node_base_interface_->get_rcl_node_handle()); - state_machine_ = rcl_lifecycle_get_zero_initialized_state_machine(); - auto state_machine_options = rcl_lifecycle_get_default_state_machine_options(); - state_machine_options.enable_com_interface = enable_communication_interface; - state_machine_options.allocator = node_options->allocator; - - // The call to initialize the state machine takes - // currently five different typesupports for all publishers/services - // created within the RCL_LIFECYCLE structure. - // The publisher takes a C-Typesupport since the publishing (i.e. creating - // the message) is done fully in RCL. - // Services are handled in C++, so that it needs a C++ typesupport structure. - rcl_ret_t ret = rcl_lifecycle_state_machine_init( - &state_machine_, - node_handle, - ROSIDL_GET_MSG_TYPE_SUPPORT(lifecycle_msgs, msg, TransitionEvent), - rosidl_typesupport_cpp::get_service_type_support_handle(), - rosidl_typesupport_cpp::get_service_type_support_handle(), - rosidl_typesupport_cpp::get_service_type_support_handle(), - rosidl_typesupport_cpp::get_service_type_support_handle(), - rosidl_typesupport_cpp::get_service_type_support_handle(), - &state_machine_options); - if (ret != RCL_RET_OK) { - throw std::runtime_error( - std::string("Couldn't initialize state machine for node ") + - node_base_interface_->get_name()); - } - - if (enable_communication_interface) { - { // change_state - auto cb = std::bind( - &LifecycleNodeInterfaceImpl::on_change_state, this, - std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::AnyServiceCallback any_cb; - any_cb.set(std::move(cb)); - - srv_change_state_ = std::make_shared>( - node_base_interface_->get_shared_rcl_node_handle(), - &state_machine_.com_interface.srv_change_state, - any_cb); - node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_change_state_), - nullptr); - } - - { // get_state - auto cb = std::bind( - &LifecycleNodeInterfaceImpl::on_get_state, this, - std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::AnyServiceCallback any_cb; - any_cb.set(std::move(cb)); - - srv_get_state_ = std::make_shared>( - node_base_interface_->get_shared_rcl_node_handle(), - &state_machine_.com_interface.srv_get_state, - any_cb); - node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_state_), - nullptr); - } - - { // get_available_states - auto cb = std::bind( - &LifecycleNodeInterfaceImpl::on_get_available_states, this, - std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::AnyServiceCallback any_cb; - any_cb.set(std::move(cb)); - - srv_get_available_states_ = std::make_shared>( - node_base_interface_->get_shared_rcl_node_handle(), - &state_machine_.com_interface.srv_get_available_states, - any_cb); - node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_available_states_), - nullptr); - } - - { // get_available_transitions - auto cb = std::bind( - &LifecycleNodeInterfaceImpl::on_get_available_transitions, this, - std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::AnyServiceCallback any_cb; - any_cb.set(std::move(cb)); - - srv_get_available_transitions_ = - std::make_shared>( - node_base_interface_->get_shared_rcl_node_handle(), - &state_machine_.com_interface.srv_get_available_transitions, - any_cb); - node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_available_transitions_), - nullptr); - } - - { // get_transition_graph - auto cb = std::bind( - &LifecycleNodeInterfaceImpl::on_get_transition_graph, this, - std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); - rclcpp::AnyServiceCallback any_cb; - any_cb.set(std::move(cb)); - - srv_get_transition_graph_ = - std::make_shared>( - node_base_interface_->get_shared_rcl_node_handle(), - &state_machine_.com_interface.srv_get_transition_graph, - any_cb); - node_services_interface_->add_service( - std::dynamic_pointer_cast(srv_get_transition_graph_), - nullptr); - } - } - } + init(bool enable_communication_interface = true); bool register_callback( std::uint8_t lifecycle_transition, - std::function & cb) - { - cb_map_[lifecycle_transition] = cb; - return true; - } + std::function & cb); + + const State & + get_current_state() const; + + std::vector + get_available_states() const; + + std::vector + get_available_transitions() const; + + std::vector + get_transition_graph() const; + + const State & + trigger_transition(uint8_t transition_id); + + const State & + trigger_transition( + uint8_t transition_id, + node_interfaces::LifecycleNodeInterface::CallbackReturn & cb_return_code); + + const State & trigger_transition(const char * transition_label); + + const State & trigger_transition( + const char * transition_label, + node_interfaces::LifecycleNodeInterface::CallbackReturn & cb_return_code); + + void + on_activate() const; + + void + on_deactivate() const; + + void + add_managed_entity(std::weak_ptr managed_entity); + + void + add_timer_handle(std::shared_ptr timer); + +private: + RCLCPP_DISABLE_COPY(LifecycleNodeInterfaceImpl) void on_change_state( const std::shared_ptr header, const std::shared_ptr req, - std::shared_ptr resp) - { - (void)header; - if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { - throw std::runtime_error( - "Can't get state. State machine is not initialized."); - } - - auto transition_id = req->transition.id; - // if there's a label attached to the request, - // we check the transition attached to this label. - // we further can't compare the id of the looked up transition - // because ros2 service call defaults all intergers to zero. - // that means if we call ros2 service call ... {transition: {label: shutdown}} - // the id of the request is 0 (zero) whereas the id from the lookup up transition - // can be different. - // the result of this is that the label takes presedence of the id. - if (req->transition.label.size() != 0) { - auto rcl_transition = rcl_lifecycle_get_transition_by_label( - state_machine_.current_state, req->transition.label.c_str()); - if (rcl_transition == nullptr) { - resp->success = false; - return; - } - transition_id = static_cast(rcl_transition->id); - } - - node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code; - auto ret = change_state(transition_id, cb_return_code); - (void) ret; - // TODO(karsten1987): Lifecycle msgs have to be extended to keep both returns - // 1. return is the actual transition - // 2. return is whether an error occurred or not - resp->success = - (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS); - } + std::shared_ptr resp); void on_get_state( const std::shared_ptr header, const std::shared_ptr req, - std::shared_ptr resp) - { - (void)header; - (void)req; - if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { - throw std::runtime_error( - "Can't get state. State machine is not initialized."); - } - resp->current_state.id = static_cast(state_machine_.current_state->id); - resp->current_state.label = state_machine_.current_state->label; - } + std::shared_ptr resp) const; void on_get_available_states( const std::shared_ptr header, const std::shared_ptr req, - std::shared_ptr resp) - { - (void)header; - (void)req; - if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { - throw std::runtime_error( - "Can't get available states. State machine is not initialized."); - } - - resp->available_states.resize(state_machine_.transition_map.states_size); - for (unsigned int i = 0; i < state_machine_.transition_map.states_size; ++i) { - resp->available_states[i].id = - static_cast(state_machine_.transition_map.states[i].id); - resp->available_states[i].label = - static_cast(state_machine_.transition_map.states[i].label); - } - } + std::shared_ptr resp) const; void on_get_available_transitions( const std::shared_ptr header, const std::shared_ptr req, - std::shared_ptr resp) - { - (void)header; - (void)req; - if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { - throw std::runtime_error( - "Can't get available transitions. State machine is not initialized."); - } - - resp->available_transitions.resize(state_machine_.current_state->valid_transition_size); - for (unsigned int i = 0; i < state_machine_.current_state->valid_transition_size; ++i) { - lifecycle_msgs::msg::TransitionDescription & trans_desc = resp->available_transitions[i]; - - auto rcl_transition = state_machine_.current_state->valid_transitions[i]; - trans_desc.transition.id = static_cast(rcl_transition.id); - trans_desc.transition.label = rcl_transition.label; - trans_desc.start_state.id = static_cast(rcl_transition.start->id); - trans_desc.start_state.label = rcl_transition.start->label; - trans_desc.goal_state.id = static_cast(rcl_transition.goal->id); - trans_desc.goal_state.label = rcl_transition.goal->label; - } - } + std::shared_ptr resp) const; void on_get_transition_graph( const std::shared_ptr header, const std::shared_ptr req, - std::shared_ptr resp) - { - (void)header; - (void)req; - if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { - throw std::runtime_error( - "Can't get available transitions. State machine is not initialized."); - } - - resp->available_transitions.resize(state_machine_.transition_map.transitions_size); - for (unsigned int i = 0; i < state_machine_.transition_map.transitions_size; ++i) { - lifecycle_msgs::msg::TransitionDescription & trans_desc = resp->available_transitions[i]; - - auto rcl_transition = state_machine_.transition_map.transitions[i]; - trans_desc.transition.id = static_cast(rcl_transition.id); - trans_desc.transition.label = rcl_transition.label; - trans_desc.start_state.id = static_cast(rcl_transition.start->id); - trans_desc.start_state.label = rcl_transition.start->label; - trans_desc.goal_state.id = static_cast(rcl_transition.goal->id); - trans_desc.goal_state.label = rcl_transition.goal->label; - } - } - - const State & - get_current_state() - { - current_state_ = State(state_machine_.current_state); - return current_state_; - } - - std::vector - get_available_states() - { - std::vector states; - states.reserve(state_machine_.transition_map.states_size); - - for (unsigned int i = 0; i < state_machine_.transition_map.states_size; ++i) { - states.emplace_back(&state_machine_.transition_map.states[i]); - } - return states; - } - - std::vector - get_available_transitions() - { - std::vector transitions; - transitions.reserve(state_machine_.current_state->valid_transition_size); - - for (unsigned int i = 0; i < state_machine_.current_state->valid_transition_size; ++i) { - transitions.emplace_back(&state_machine_.current_state->valid_transitions[i]); - } - return transitions; - } - - std::vector - get_transition_graph() - { - std::vector transitions; - transitions.reserve(state_machine_.transition_map.transitions_size); - - for (unsigned int i = 0; i < state_machine_.transition_map.transitions_size; ++i) { - transitions.emplace_back(&state_machine_.transition_map.transitions[i]); - } - return transitions; - } + std::shared_ptr resp) const; rcl_ret_t - change_state(std::uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code) - { - if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) { - RCUTILS_LOG_ERROR( - "Unable to change state for state machine for %s: %s", - node_base_interface_->get_name(), rcl_get_error_string().str); - return RCL_RET_ERROR; - } - - constexpr bool publish_update = true; - // keep the initial state to pass to a transition callback - State initial_state(state_machine_.current_state); - - if ( - rcl_lifecycle_trigger_transition_by_id( - &state_machine_, transition_id, publish_update) != RCL_RET_OK) - { - RCUTILS_LOG_ERROR( - "Unable to start transition %u from current state %s: %s", - transition_id, state_machine_.current_state->label, rcl_get_error_string().str); - rcutils_reset_error(); - return RCL_RET_ERROR; - } - - auto get_label_for_return_code = - [](node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code) -> const char *{ - auto cb_id = static_cast(cb_return_code); - if (cb_id == lifecycle_msgs::msg::Transition::TRANSITION_CALLBACK_SUCCESS) { - return rcl_lifecycle_transition_success_label; - } else if (cb_id == lifecycle_msgs::msg::Transition::TRANSITION_CALLBACK_FAILURE) { - return rcl_lifecycle_transition_failure_label; - } - return rcl_lifecycle_transition_error_label; - }; - - cb_return_code = execute_callback(state_machine_.current_state->id, initial_state); - auto transition_label = get_label_for_return_code(cb_return_code); - - if ( - rcl_lifecycle_trigger_transition_by_label( - &state_machine_, transition_label, publish_update) != RCL_RET_OK) - { - RCUTILS_LOG_ERROR( - "Failed to finish transition %u. Current state is now: %s (%s)", - transition_id, state_machine_.current_state->label, rcl_get_error_string().str); - rcutils_reset_error(); - return RCL_RET_ERROR; - } - - // error handling ?! - // TODO(karsten1987): iterate over possible ret value - if (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR) { - RCUTILS_LOG_WARN("Error occurred while doing error handling."); - - auto error_cb_code = execute_callback(state_machine_.current_state->id, initial_state); - auto error_cb_label = get_label_for_return_code(error_cb_code); - if ( - rcl_lifecycle_trigger_transition_by_label( - &state_machine_, error_cb_label, publish_update) != RCL_RET_OK) - { - RCUTILS_LOG_ERROR("Failed to call cleanup on error state: %s", rcl_get_error_string().str); - rcutils_reset_error(); - return RCL_RET_ERROR; - } - } - // This true holds in both cases where the actual callback - // was successful or not, since at this point we have a valid transistion - // to either a new primary state or error state - return RCL_RET_OK; - } - - LifecycleNodeInterface::CallbackReturn - execute_callback(unsigned int cb_id, const State & previous_state) - { - // in case no callback was attached, we forward directly - auto cb_success = node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; - - auto it = cb_map_.find(static_cast(cb_id)); - if (it != cb_map_.end()) { - auto callback = it->second; - try { - cb_success = callback(State(previous_state)); - } catch (const std::exception & e) { - RCUTILS_LOG_ERROR("Caught exception in callback for transition %d", it->first); - RCUTILS_LOG_ERROR("Original error: %s", e.what()); - cb_success = node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; - } - } - return cb_success; - } - - const State & trigger_transition(const char * transition_label) - { - LifecycleNodeInterface::CallbackReturn error; - return trigger_transition(transition_label, error); - } + change_state( + std::uint8_t transition_id, + node_interfaces::LifecycleNodeInterface::CallbackReturn & cb_return_code); - const State & trigger_transition( - const char * transition_label, LifecycleNodeInterface::CallbackReturn & cb_return_code) - { - auto transition = - rcl_lifecycle_get_transition_by_label(state_machine_.current_state, transition_label); - if (transition) { - change_state(static_cast(transition->id), cb_return_code); - } - return get_current_state(); - } - - const State & - trigger_transition(uint8_t transition_id) - { - LifecycleNodeInterface::CallbackReturn error; - change_state(transition_id, error); - (void) error; - return get_current_state(); - } - - const State & - trigger_transition(uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code) - { - change_state(transition_id, cb_return_code); - return get_current_state(); - } - - void - add_managed_entity(std::weak_ptr managed_entity) - { - weak_managed_entities_.push_back(managed_entity); - } - - void - add_timer_handle(std::shared_ptr timer) - { - weak_timers_.push_back(timer); - } - - void - on_activate() - { - for (const auto & weak_entity : weak_managed_entities_) { - auto entity = weak_entity.lock(); - if (entity) { - entity->on_activate(); - } - } - } - - void - on_deactivate() - { - for (const auto & weak_entity : weak_managed_entities_) { - auto entity = weak_entity.lock(); - if (entity) { - entity->on_deactivate(); - } - } - } + node_interfaces::LifecycleNodeInterface::CallbackReturn + execute_callback(unsigned int cb_id, const State & previous_state) const; + mutable std::recursive_mutex state_machine_mutex_; rcl_lifecycle_state_machine_t state_machine_; State current_state_; std::map< std::uint8_t, - std::function> cb_map_; + std::function> cb_map_; using NodeBasePtr = std::shared_ptr; using NodeServicesPtr = std::shared_ptr; diff --git a/rclcpp_lifecycle/src/node_interfaces/lifecycle_node_interface.cpp b/rclcpp_lifecycle/src/node_interfaces/lifecycle_node_interface.cpp index 1c8a5a646a..06b889be05 100644 --- a/rclcpp_lifecycle/src/node_interfaces/lifecycle_node_interface.cpp +++ b/rclcpp_lifecycle/src/node_interfaces/lifecycle_node_interface.cpp @@ -14,7 +14,7 @@ #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" -#include "rcl_lifecycle/rcl_lifecycle.h" +#include "rclcpp_lifecycle/state.hpp" namespace rclcpp_lifecycle { diff --git a/rclcpp_lifecycle/src/state.cpp b/rclcpp_lifecycle/src/state.cpp index f7aca2688e..e69078dfba 100644 --- a/rclcpp_lifecycle/src/state.cpp +++ b/rclcpp_lifecycle/src/state.cpp @@ -14,6 +14,7 @@ #include "rclcpp_lifecycle/state.hpp" +#include #include #include "lifecycle_msgs/msg/state.hpp" @@ -70,6 +71,7 @@ State::State( if (!rcl_lifecycle_state_handle) { throw std::runtime_error("rcl_lifecycle_state_handle is null"); } + state_handle_ = const_cast(rcl_lifecycle_state_handle); } @@ -93,6 +95,8 @@ State::operator=(const State & rhs) return *this; } + // hold the lock until state_handle_ is reconstructed + std::lock_guard lock(state_handle_mutex_); // reset all currently used resources reset(); @@ -128,6 +132,7 @@ State::operator=(const State & rhs) uint8_t State::id() const { + std::lock_guard lock(state_handle_mutex_); if (!state_handle_) { throw std::runtime_error("Error in state! Internal state_handle is NULL."); } @@ -137,6 +142,7 @@ State::id() const std::string State::label() const { + std::lock_guard lock(state_handle_mutex_); if (!state_handle_) { throw std::runtime_error("Error in state! Internal state_handle is NULL."); } @@ -146,6 +152,7 @@ State::label() const void State::reset() noexcept { + std::lock_guard lock(state_handle_mutex_); if (!owns_rcl_state_handle_) { state_handle_ = nullptr; } diff --git a/rclcpp_lifecycle/src/transition.cpp b/rclcpp_lifecycle/src/transition.cpp index 50f0b33735..360c1cfb13 100644 --- a/rclcpp_lifecycle/src/transition.cpp +++ b/rclcpp_lifecycle/src/transition.cpp @@ -14,6 +14,7 @@ #include "rclcpp_lifecycle/transition.hpp" +#include #include #include "lifecycle_msgs/msg/transition.hpp" diff --git a/rclcpp_lifecycle/test/test_client.cpp b/rclcpp_lifecycle/test/test_client.cpp new file mode 100644 index 0000000000..7ded8e346e --- /dev/null +++ b/rclcpp_lifecycle/test/test_client.cpp @@ -0,0 +1,144 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +#include "rclcpp/exceptions.hpp" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_lifecycle/lifecycle_node.hpp" + +#include "rcl_interfaces/srv/list_parameters.hpp" + +#include "rmw/qos_profiles.h" + +class TestClient : public ::testing::Test +{ +protected: + static void SetUpTestCase() + { + rclcpp::init(0, nullptr); + } + + static void TearDownTestCase() + { + rclcpp::shutdown(); + } + + void SetUp() + { + node_ = std::make_shared("my_lifecycle_node", "/ns"); + } + + void TearDown() + { + node_.reset(); + } + + rclcpp_lifecycle::LifecycleNode::SharedPtr node_; +}; + +/* + Testing client construction and destruction. + */ +TEST_F(TestClient, construction_and_destruction) { + using rcl_interfaces::srv::ListParameters; + { + auto client = node_->create_client("service"); + EXPECT_TRUE(client); + } + { + // suppress deprecated function warning + #if !defined(_WIN32) + # pragma GCC diagnostic push + # pragma GCC diagnostic ignored "-Wdeprecated-declarations" + #else // !defined(_WIN32) + # pragma warning(push) + # pragma warning(disable: 4996) + #endif + + auto client = node_->create_client( + "service", rmw_qos_profile_services_default); + EXPECT_TRUE(client); + + // remove warning suppression + #if !defined(_WIN32) + # pragma GCC diagnostic pop + #else // !defined(_WIN32) + # pragma warning(pop) + #endif + } + { + auto client = node_->create_client( + "service", rclcpp::ServicesQoS()); + EXPECT_TRUE(client); + } + + { + ASSERT_THROW( + { + auto client = node_->create_client("invalid_service?"); + }, rclcpp::exceptions::InvalidServiceNameError); + } +} + +TEST_F(TestClient, construction_with_free_function) { + { + auto client = rclcpp::create_client( + node_->get_node_base_interface(), + node_->get_node_graph_interface(), + node_->get_node_services_interface(), + "service", + rmw_qos_profile_services_default, + nullptr); + EXPECT_TRUE(client); + } + { + ASSERT_THROW( + { + auto client = rclcpp::create_client( + node_->get_node_base_interface(), + node_->get_node_graph_interface(), + node_->get_node_services_interface(), + "invalid_?service", + rmw_qos_profile_services_default, + nullptr); + }, rclcpp::exceptions::InvalidServiceNameError); + } + { + auto client = rclcpp::create_client( + node_->get_node_base_interface(), + node_->get_node_graph_interface(), + node_->get_node_services_interface(), + "service", + rclcpp::ServicesQoS(), + nullptr); + EXPECT_TRUE(client); + } + { + ASSERT_THROW( + { + auto client = rclcpp::create_client( + node_->get_node_base_interface(), + node_->get_node_graph_interface(), + node_->get_node_services_interface(), + "invalid_?service", + rclcpp::ServicesQoS(), + nullptr); + }, rclcpp::exceptions::InvalidServiceNameError); + } +} diff --git a/rclcpp_lifecycle/test/test_lifecycle_publisher.cpp b/rclcpp_lifecycle/test/test_lifecycle_publisher.cpp index 2a5d08f728..d10544ef1f 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_publisher.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_publisher.cpp @@ -42,10 +42,17 @@ class TestDefaultStateMachine : public ::testing::Test } }; +/// We want to test everything for both the wall and generic timer. +enum class TimerType +{ + WALL_TIMER, + GENERIC_TIMER, +}; + class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode { public: - explicit EmptyLifecycleNode(const std::string & node_name) + explicit EmptyLifecycleNode(const std::string & node_name, const TimerType & timer_type) : rclcpp_lifecycle::LifecycleNode(node_name) { rclcpp::PublisherOptionsWithAllocator> options; @@ -55,8 +62,20 @@ class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode add_managed_entity(publisher_); // For coverage this is being added here - auto timer = create_wall_timer(std::chrono::seconds(1), []() {}); - add_timer_handle(timer); + switch (timer_type) { + case TimerType::WALL_TIMER: + { + auto timer = create_wall_timer(std::chrono::seconds(1), []() {}); + add_timer_handle(timer); + break; + } + case TimerType::GENERIC_TIMER: + { + auto timer = create_timer(std::chrono::seconds(1), []() {}); + add_timer_handle(timer); + break; + } + } } std::shared_ptr> publisher() @@ -68,13 +87,13 @@ class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode std::shared_ptr> publisher_; }; -class TestLifecyclePublisher : public ::testing::Test +class TestLifecyclePublisher : public ::testing::TestWithParam { public: void SetUp() { rclcpp::init(0, nullptr); - node_ = std::make_shared("node"); + node_ = std::make_shared("node", GetParam()); } void TearDown() @@ -86,7 +105,7 @@ class TestLifecyclePublisher : public ::testing::Test std::shared_ptr node_; }; -TEST_F(TestLifecyclePublisher, publish_managed_by_node) { +TEST_P(TestLifecyclePublisher, publish_managed_by_node) { // transition via LifecycleNode auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; @@ -125,7 +144,7 @@ TEST_F(TestLifecyclePublisher, publish_managed_by_node) { } } -TEST_F(TestLifecyclePublisher, publish) { +TEST_P(TestLifecyclePublisher, publish) { // transition via LifecyclePublisher node_->publisher()->on_deactivate(); EXPECT_FALSE(node_->publisher()->is_activated()); @@ -148,3 +167,19 @@ TEST_F(TestLifecyclePublisher, publish) { EXPECT_NO_THROW(node_->publisher()->publish(std::move(msg_ptr))); } } + +INSTANTIATE_TEST_SUITE_P( + PerTimerType, TestLifecyclePublisher, + ::testing::Values(TimerType::WALL_TIMER, TimerType::GENERIC_TIMER), + [](const ::testing::TestParamInfo & info) -> std::string { + switch (info.param) { + case TimerType::WALL_TIMER: + return std::string("wall_timer"); + case TimerType::GENERIC_TIMER: + return std::string("generic_timer"); + default: + break; + } + return std::string("unknown"); + } +); diff --git a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp index 6dd2c0ec17..3698c807f6 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp @@ -33,6 +33,8 @@ #include "lifecycle_msgs/srv/get_available_transitions.hpp" #include "lifecycle_msgs/srv/get_state.hpp" +#include "rcl_lifecycle/rcl_lifecycle.h" + #include "rclcpp/node_interfaces/node_graph.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" diff --git a/rclcpp_lifecycle/test/test_service.cpp b/rclcpp_lifecycle/test/test_service.cpp new file mode 100644 index 0000000000..b3108a9042 --- /dev/null +++ b/rclcpp_lifecycle/test/test_service.cpp @@ -0,0 +1,102 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +#include "rclcpp/exceptions.hpp" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_lifecycle/lifecycle_node.hpp" + +#include "rmw/qos_profiles.h" + +#include "test_msgs/srv/empty.hpp" + +using namespace std::chrono_literals; + +class TestService : public ::testing::Test +{ +protected: + static void SetUpTestCase() + { + rclcpp::init(0, nullptr); + } + + static void TearDownTestCase() + { + rclcpp::shutdown(); + } + + void SetUp() + { + node = std::make_shared("my_lifecycle_node", "/ns"); + } + + void TearDown() + { + node.reset(); + } + + rclcpp_lifecycle::LifecycleNode::SharedPtr node; +}; + +/* + Testing service construction and destruction. + */ +TEST_F(TestService, construction_and_destruction) { + using test_msgs::srv::Empty; + auto callback = + [](const Empty::Request::SharedPtr, Empty::Response::SharedPtr) { + }; + { + auto service = node->create_service("service", callback); + EXPECT_NE(nullptr, service->get_service_handle()); + const rclcpp::ServiceBase * const_service_base = service.get(); + EXPECT_NE(nullptr, const_service_base->get_service_handle()); + } + { + // suppress deprecated function warning + #if !defined(_WIN32) + # pragma GCC diagnostic push + # pragma GCC diagnostic ignored "-Wdeprecated-declarations" + #else // !defined(_WIN32) + # pragma warning(push) + # pragma warning(disable: 4996) + #endif + + auto service = node->create_service( + "service", callback, rmw_qos_profile_services_default); + + // remove warning suppression + #if !defined(_WIN32) + # pragma GCC diagnostic pop + #else // !defined(_WIN32) + # pragma warning(pop) + #endif + + EXPECT_NE(nullptr, service->get_service_handle()); + const rclcpp::ServiceBase * const_service_base = service.get(); + EXPECT_NE(nullptr, const_service_base->get_service_handle()); + } + + { + ASSERT_THROW( + { + auto service = node->create_service("invalid_service?", callback); + }, rclcpp::exceptions::InvalidServiceNameError); + } +} diff --git a/rclcpp_lifecycle/test/test_transition_wrapper.cpp b/rclcpp_lifecycle/test/test_transition_wrapper.cpp index 4f72d90bb6..39791d5da2 100644 --- a/rclcpp_lifecycle/test/test_transition_wrapper.cpp +++ b/rclcpp_lifecycle/test/test_transition_wrapper.cpp @@ -18,10 +18,12 @@ #include #include -#include "rcutils/testing/fault_injection.h" +#include "rcl_lifecycle/rcl_lifecycle.h" #include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "rcutils/testing/fault_injection.h" + #include "./mocking_utils/patch.hpp" class TestTransitionWrapper : public ::testing::Test