From df3c2ffa8a9d0b1b6f5cf707986accbc091575f9 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Thu, 23 Apr 2020 15:28:45 -0700 Subject: [PATCH] deprecate redundant namespaces (#1083) * deprecate redundant namespaces, move classes to own files, rename some classes Signed-off-by: William Woodall * fixup Signed-off-by: William Woodall * address review comments Signed-off-by: William Woodall * fix ups since rebase Signed-off-by: William Woodall * avoid deprecation warnings from deprecated functions Signed-off-by: William Woodall * more fixes Signed-off-by: William Woodall * another fixup, after another rebase Signed-off-by: William Woodall --- rclcpp/CMakeLists.txt | 3 +- rclcpp/include/rclcpp/any_executable.hpp | 9 +- rclcpp/include/rclcpp/callback_group.hpp | 9 +- .../rclcpp/contexts/default_context.hpp | 17 +- rclcpp/include/rclcpp/create_client.hpp | 2 +- rclcpp/include/rclcpp/create_service.hpp | 2 +- rclcpp/include/rclcpp/create_timer.hpp | 6 +- rclcpp/include/rclcpp/exceptions.hpp | 261 +--------------- .../include/rclcpp/exceptions/exceptions.hpp | 279 ++++++++++++++++++ rclcpp/include/rclcpp/executor.hpp | 59 +--- rclcpp/include/rclcpp/executor_options.hpp | 57 ++++ rclcpp/include/rclcpp/executors.hpp | 12 +- .../executors/multi_threaded_executor.hpp | 6 +- .../executors/single_threaded_executor.hpp | 22 +- .../static_executor_entities_collector.hpp | 4 +- .../static_single_threaded_executor.hpp | 16 +- .../{ => experimental}/executable_list.hpp | 10 +- rclcpp/include/rclcpp/future_return_code.hpp | 61 ++++ rclcpp/include/rclcpp/guard_condition.hpp | 2 +- rclcpp/include/rclcpp/memory_strategy.hpp | 22 +- rclcpp/include/rclcpp/node.hpp | 14 +- rclcpp/include/rclcpp/node_impl.hpp | 6 +- .../rclcpp/node_interfaces/node_base.hpp | 14 +- .../node_interfaces/node_base_interface.hpp | 10 +- .../rclcpp/node_interfaces/node_services.hpp | 4 +- .../node_services_interface.hpp | 4 +- .../rclcpp/node_interfaces/node_timers.hpp | 2 +- .../node_interfaces/node_timers_interface.hpp | 2 +- .../rclcpp/node_interfaces/node_topics.hpp | 4 +- .../node_interfaces/node_topics_interface.hpp | 4 +- .../rclcpp/node_interfaces/node_waitables.hpp | 4 +- .../node_waitables_interface.hpp | 4 +- rclcpp/include/rclcpp/node_options.hpp | 4 +- rclcpp/include/rclcpp/parameter_client.hpp | 14 +- rclcpp/include/rclcpp/publisher_options.hpp | 5 +- rclcpp/include/rclcpp/rclcpp.hpp | 2 +- .../strategies/allocator_memory_strategy.hpp | 10 +- .../message_pool_memory_strategy.hpp | 2 + .../include/rclcpp/subscription_options.hpp | 2 +- rclcpp/include/rclcpp/utilities.hpp | 2 +- rclcpp/include/rclcpp/wait_set_template.hpp | 2 +- rclcpp/src/rclcpp/any_executable.cpp | 2 +- rclcpp/src/rclcpp/callback_group.cpp | 4 +- .../src/rclcpp/contexts/default_context.cpp | 4 +- .../rclcpp/{ => exceptions}/exceptions.cpp | 0 rclcpp/src/rclcpp/executable_list.cpp | 4 +- rclcpp/src/rclcpp/executor.cpp | 50 +--- .../executors/multi_threaded_executor.cpp | 6 +- .../executors/single_threaded_executor.cpp | 6 +- .../static_executor_entities_collector.cpp | 2 +- .../static_single_threaded_executor.cpp | 6 +- rclcpp/src/rclcpp/future_return_code.cpp | 50 ++++ rclcpp/src/rclcpp/memory_strategy.cpp | 12 +- rclcpp/src/rclcpp/node.cpp | 9 +- .../src/rclcpp/node_interfaces/node_base.cpp | 16 +- .../rclcpp/node_interfaces/node_services.cpp | 4 +- .../rclcpp/node_interfaces/node_timers.cpp | 2 +- .../rclcpp/node_interfaces/node_topics.cpp | 4 +- .../rclcpp/node_interfaces/node_waitables.cpp | 4 +- rclcpp/src/rclcpp/parameter_client.cpp | 22 +- rclcpp/src/rclcpp/timer.cpp | 2 +- rclcpp/src/rclcpp/utilities.cpp | 10 +- .../test_multi_threaded_executor.cpp | 4 +- rclcpp/test/test_interface_traits.cpp | 2 +- rclcpp/test/test_utilities.cpp | 4 +- .../include/rclcpp_action/create_client.hpp | 8 +- .../include/rclcpp_action/create_server.hpp | 6 +- rclcpp_action/test/test_server.cpp | 8 +- .../rclcpp_components/component_manager.hpp | 4 +- rclcpp_components/src/component_manager.cpp | 2 +- .../test/test_component_manager_api.cpp | 20 +- .../rclcpp_lifecycle/lifecycle_node.hpp | 14 +- .../rclcpp_lifecycle/lifecycle_node_impl.hpp | 6 +- rclcpp_lifecycle/src/lifecycle_node.cpp | 8 +- 74 files changed, 716 insertions(+), 563 deletions(-) create mode 100644 rclcpp/include/rclcpp/exceptions/exceptions.hpp create mode 100644 rclcpp/include/rclcpp/executor_options.hpp rename rclcpp/include/rclcpp/{ => experimental}/executable_list.hpp (92%) create mode 100644 rclcpp/include/rclcpp/future_return_code.hpp rename rclcpp/src/rclcpp/{ => exceptions}/exceptions.cpp (100%) create mode 100644 rclcpp/src/rclcpp/future_return_code.cpp diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index fbb910533f..518951017b 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -39,7 +39,7 @@ set(${PROJECT_NAME}_SRCS src/rclcpp/detail/utilities.cpp src/rclcpp/duration.cpp src/rclcpp/event.cpp - src/rclcpp/exceptions.cpp + src/rclcpp/exceptions/exceptions.cpp src/rclcpp/executable_list.cpp src/rclcpp/executor.cpp src/rclcpp/executors.cpp @@ -48,6 +48,7 @@ set(${PROJECT_NAME}_SRCS src/rclcpp/executors/single_threaded_executor.cpp src/rclcpp/executors/static_executor_entities_collector.cpp src/rclcpp/executors/static_single_threaded_executor.cpp + src/rclcpp/future_return_code.cpp src/rclcpp/graph_listener.cpp src/rclcpp/guard_condition.cpp src/rclcpp/init_options.cpp diff --git a/rclcpp/include/rclcpp/any_executable.hpp b/rclcpp/include/rclcpp/any_executable.hpp index aae25dca78..675d46554f 100644 --- a/rclcpp/include/rclcpp/any_executable.hpp +++ b/rclcpp/include/rclcpp/any_executable.hpp @@ -29,8 +29,6 @@ namespace rclcpp { -namespace executor -{ struct AnyExecutable { @@ -47,10 +45,15 @@ struct AnyExecutable rclcpp::ClientBase::SharedPtr client; rclcpp::Waitable::SharedPtr waitable; // These are used to keep the scope on the containing items - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group; + rclcpp::CallbackGroup::SharedPtr callback_group; rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base; }; +namespace executor +{ + +using AnyExecutable [[deprecated("use rclcpp::AnyExecutable instead")]] = AnyExecutable; + } // namespace executor } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index ef87a2f032..5e1157f204 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -40,9 +40,6 @@ class NodeTopics; class NodeWaitables; } // namespace node_interfaces -namespace callback_group -{ - enum class CallbackGroupType { MutuallyExclusive, @@ -162,6 +159,12 @@ class CallbackGroup } }; +namespace callback_group +{ + +using CallbackGroupType [[deprecated("use rclcpp::CallbackGroupType instead")]] = CallbackGroupType; +using CallbackGroup [[deprecated("use rclcpp::CallbackGroup instead")]] = CallbackGroup; + } // namespace callback_group } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/contexts/default_context.hpp b/rclcpp/include/rclcpp/contexts/default_context.hpp index 2ed9bcbbf1..0c2bbf8265 100644 --- a/rclcpp/include/rclcpp/contexts/default_context.hpp +++ b/rclcpp/include/rclcpp/contexts/default_context.hpp @@ -22,8 +22,6 @@ namespace rclcpp { namespace contexts { -namespace default_context -{ class DefaultContext : public rclcpp::Context { @@ -38,6 +36,21 @@ RCLCPP_PUBLIC DefaultContext::SharedPtr get_global_default_context(); +namespace default_context +{ + +using DefaultContext +[[deprecated("use rclcpp::contexts::DefaultContext instead")]] = DefaultContext; + +[[deprecated("use rclcpp::contexts::get_global_default_context() instead")]] +RCLCPP_PUBLIC +inline +DefaultContext::SharedPtr +get_global_default_context() +{ + return rclcpp::contexts::get_global_default_context(); +} + } // namespace default_context } // namespace contexts } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/create_client.hpp b/rclcpp/include/rclcpp/create_client.hpp index 94f6b212fa..1a960b8d8f 100644 --- a/rclcpp/include/rclcpp/create_client.hpp +++ b/rclcpp/include/rclcpp/create_client.hpp @@ -35,7 +35,7 @@ create_client( std::shared_ptr node_services, const std::string & service_name, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { rcl_client_options_t options = rcl_client_get_default_options(); options.qos = qos_profile; diff --git a/rclcpp/include/rclcpp/create_service.hpp b/rclcpp/include/rclcpp/create_service.hpp index ac7846239d..9aaa02a1ed 100644 --- a/rclcpp/include/rclcpp/create_service.hpp +++ b/rclcpp/include/rclcpp/create_service.hpp @@ -37,7 +37,7 @@ create_service( const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { rclcpp::AnyServiceCallback any_service_callback; any_service_callback.set(std::forward(callback)); diff --git a/rclcpp/include/rclcpp/create_timer.hpp b/rclcpp/include/rclcpp/create_timer.hpp index ed2965b01c..f7b810dc4d 100644 --- a/rclcpp/include/rclcpp/create_timer.hpp +++ b/rclcpp/include/rclcpp/create_timer.hpp @@ -39,7 +39,7 @@ create_timer( rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT && callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr) + rclcpp::CallbackGroup::SharedPtr group = nullptr) { auto timer = rclcpp::GenericTimer::make_shared( clock, @@ -59,7 +59,7 @@ create_timer( rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT && callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr) + rclcpp::CallbackGroup::SharedPtr group = nullptr) { return create_timer( rclcpp::node_interfaces::get_node_base_interface(node), @@ -90,7 +90,7 @@ typename rclcpp::WallTimer::SharedPtr create_wall_timer( std::chrono::duration period, CallbackT callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group, + rclcpp::CallbackGroup::SharedPtr group, node_interfaces::NodeBaseInterface * node_base, node_interfaces::NodeTimersInterface * node_timers) { diff --git a/rclcpp/include/rclcpp/exceptions.hpp b/rclcpp/include/rclcpp/exceptions.hpp index 4fe5988113..dcac558512 100644 --- a/rclcpp/include/rclcpp/exceptions.hpp +++ b/rclcpp/include/rclcpp/exceptions.hpp @@ -15,265 +15,6 @@ #ifndef RCLCPP__EXCEPTIONS_HPP_ #define RCLCPP__EXCEPTIONS_HPP_ -#include -#include -#include - -#include "rcl/error_handling.h" -#include "rcl/types.h" -#include "rclcpp/visibility_control.hpp" - -#include "rcpputils/join.hpp" - -namespace rclcpp -{ -namespace exceptions -{ - -/// Thrown when a method is trying to use a node, but it is invalid. -class InvalidNodeError : public std::runtime_error -{ -public: - InvalidNodeError() - : std::runtime_error("node is invalid") {} -}; - -/// Thrown when a any kind of name (node, namespace, topic, etc.) is invalid. -class NameValidationError : public std::invalid_argument -{ -public: - NameValidationError( - const char * name_type_, - const char * name_, - const char * error_msg_, - size_t invalid_index_) - : std::invalid_argument(format_error(name_type_, name_, error_msg_, invalid_index_)), - name_type(name_type_), name(name_), error_msg(error_msg_), invalid_index(invalid_index_) - {} - - static std::string - format_error( - const char * name_type, - const char * name, - const char * error_msg, - size_t invalid_index); - - const std::string name_type; - const std::string name; - const std::string error_msg; - const size_t invalid_index; -}; - -/// Thrown when a node name is invalid. -class InvalidNodeNameError : public NameValidationError -{ -public: - InvalidNodeNameError(const char * node_name, const char * error_msg, size_t invalid_index) - : NameValidationError("node name", node_name, error_msg, invalid_index) - {} -}; - -/// Thrown when a node namespace is invalid. -class InvalidNamespaceError : public NameValidationError -{ -public: - InvalidNamespaceError(const char * namespace_, const char * error_msg, size_t invalid_index) - : NameValidationError("namespace", namespace_, error_msg, invalid_index) - {} -}; - -/// Thrown when a topic name is invalid. -class InvalidTopicNameError : public NameValidationError -{ -public: - InvalidTopicNameError(const char * namespace_, const char * error_msg, size_t invalid_index) - : NameValidationError("topic name", namespace_, error_msg, invalid_index) - {} -}; - -/// Thrown when a service name is invalid. -class InvalidServiceNameError : public NameValidationError -{ -public: - InvalidServiceNameError(const char * namespace_, const char * error_msg, size_t invalid_index) - : NameValidationError("service name", namespace_, error_msg, invalid_index) - {} -}; - -/// Throw a C++ std::exception which was created based on an rcl error. -/** - * Passing nullptr for reset_error is safe and will avoid calling any function - * to reset the error. - * - * \param ret the return code for the current error state - * \param prefix string to prefix to the error if applicable (not all errors have custom messages) - * \param error_state error state to create exception from, if nullptr rcl_get_error_state is used - * \param reset_error function to be called before throwing which whill clear the error state - * \throws std::invalid_argument if ret is RCL_RET_OK - * \throws std::runtime_error if the rcl_get_error_state returns 0 - * \throws RCLErrorBase some child class exception based on ret - */ -/* *INDENT-OFF* */ // Uncrustify cannot yet understand [[noreturn]] properly -RCLCPP_PUBLIC -void -throw_from_rcl_error [[noreturn]] ( - rcl_ret_t ret, - const std::string & prefix = "", - const rcl_error_state_t * error_state = nullptr, - void (* reset_error)() = rcl_reset_error); -/* *INDENT-ON* */ - -class RCLErrorBase -{ -public: - RCLCPP_PUBLIC - RCLErrorBase(rcl_ret_t ret, const rcl_error_state_t * error_state); - virtual ~RCLErrorBase() {} - - rcl_ret_t ret; - std::string message; - std::string file; - size_t line; - std::string formatted_message; -}; - -/// Created when the return code does not match one of the other specialized exceptions. -class RCLError : public RCLErrorBase, public std::runtime_error -{ -public: - RCLCPP_PUBLIC - RCLError(rcl_ret_t ret, const rcl_error_state_t * error_state, const std::string & prefix); - RCLCPP_PUBLIC - RCLError(const RCLErrorBase & base_exc, const std::string & prefix); -}; - -/// Created when the ret is RCL_RET_BAD_ALLOC. -class RCLBadAlloc : public RCLErrorBase, public std::bad_alloc -{ -public: - RCLCPP_PUBLIC - RCLBadAlloc(rcl_ret_t ret, const rcl_error_state_t * error_state); - RCLCPP_PUBLIC - explicit RCLBadAlloc(const RCLErrorBase & base_exc); -}; - -/// Created when the ret is RCL_RET_INVALID_ARGUMENT. -class RCLInvalidArgument : public RCLErrorBase, public std::invalid_argument -{ -public: - RCLCPP_PUBLIC - RCLInvalidArgument( - rcl_ret_t ret, - const rcl_error_state_t * error_state, - const std::string & prefix); - RCLCPP_PUBLIC - RCLInvalidArgument(const RCLErrorBase & base_exc, const std::string & prefix); -}; - -/// Created when the ret is RCL_RET_INVALID_ROS_ARGS. -class RCLInvalidROSArgsError : public RCLErrorBase, public std::runtime_error -{ -public: - RCLCPP_PUBLIC - RCLInvalidROSArgsError( - rcl_ret_t ret, const rcl_error_state_t * error_state, const std::string & prefix); - RCLCPP_PUBLIC - RCLInvalidROSArgsError(const RCLErrorBase & base_exc, const std::string & prefix); -}; - -/// Thrown when unparsed ROS specific arguments are found. -class UnknownROSArgsError : public std::runtime_error -{ -public: - explicit UnknownROSArgsError(std::vector && unknown_ros_args_in) - : std::runtime_error( - "found unknown ROS arguments: '" + rcpputils::join(unknown_ros_args_in, "', '") + "'"), - unknown_ros_args(unknown_ros_args_in) - { - } - - const std::vector unknown_ros_args; -}; - -/// Thrown when an invalid rclcpp::Event object or SharedPtr is encountered. -class InvalidEventError : public std::runtime_error -{ -public: - InvalidEventError() - : std::runtime_error("event is invalid") {} -}; - -/// Thrown when an unregistered rclcpp::Event is encountered where a registered one was expected. -class EventNotRegisteredError : public std::runtime_error -{ -public: - EventNotRegisteredError() - : std::runtime_error("event already registered") {} -}; - -/// Thrown if passed parameters are inconsistent or invalid -class InvalidParametersException : public std::runtime_error -{ -public: - // Inherit constructors from runtime_error. - using std::runtime_error::runtime_error; -}; - -/// Thrown if passed parameter value is invalid. -class InvalidParameterValueException : public std::runtime_error -{ - // Inherit constructors from runtime_error. - using std::runtime_error::runtime_error; -}; - -/// Thrown if requested parameter type is invalid. -/** - * Essentially the same as rclcpp::ParameterTypeException, but with parameter - * name in the error message. - */ -class InvalidParameterTypeException : public std::runtime_error -{ -public: - /// Construct an instance. - /** - * \param[in] name the name of the parameter. - * \param[in] message custom exception message. - */ - RCLCPP_PUBLIC - InvalidParameterTypeException(const std::string & name, const std::string message) - : std::runtime_error("parameter '" + name + "' has invalid type: " + message) - {} -}; - -/// Thrown if parameter is already declared. -class ParameterAlreadyDeclaredException : public std::runtime_error -{ - // Inherit constructors from runtime_error. - using std::runtime_error::runtime_error; -}; - -/// Thrown if parameter is not declared, e.g. either set or get was called without first declaring. -class ParameterNotDeclaredException : public std::runtime_error -{ - // Inherit constructors from runtime_error. - using std::runtime_error::runtime_error; -}; - -/// Thrown if parameter is immutable and therefore cannot be undeclared. -class ParameterImmutableException : public std::runtime_error -{ - // Inherit constructors from runtime_error. - using std::runtime_error::runtime_error; -}; - -/// Thrown if parameter is modified while in a set callback. -class ParameterModifiedInCallbackException : public std::runtime_error -{ - // Inherit constructors from runtime_error. - using std::runtime_error::runtime_error; -}; - -} // namespace exceptions -} // namespace rclcpp +#include "rclcpp/exceptions/exceptions.hpp" #endif // RCLCPP__EXCEPTIONS_HPP_ diff --git a/rclcpp/include/rclcpp/exceptions/exceptions.hpp b/rclcpp/include/rclcpp/exceptions/exceptions.hpp new file mode 100644 index 0000000000..d501acd71c --- /dev/null +++ b/rclcpp/include/rclcpp/exceptions/exceptions.hpp @@ -0,0 +1,279 @@ +// 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. + +#ifndef RCLCPP__EXCEPTIONS__EXCEPTIONS_HPP_ +#define RCLCPP__EXCEPTIONS__EXCEPTIONS_HPP_ + +#include +#include +#include + +#include "rcl/error_handling.h" +#include "rcl/types.h" +#include "rclcpp/visibility_control.hpp" + +#include "rcpputils/join.hpp" + +namespace rclcpp +{ +namespace exceptions +{ + +/// Thrown when a method is trying to use a node, but it is invalid. +class InvalidNodeError : public std::runtime_error +{ +public: + InvalidNodeError() + : std::runtime_error("node is invalid") {} +}; + +/// Thrown when a any kind of name (node, namespace, topic, etc.) is invalid. +class NameValidationError : public std::invalid_argument +{ +public: + NameValidationError( + const char * name_type_, + const char * name_, + const char * error_msg_, + size_t invalid_index_) + : std::invalid_argument(format_error(name_type_, name_, error_msg_, invalid_index_)), + name_type(name_type_), name(name_), error_msg(error_msg_), invalid_index(invalid_index_) + {} + + static std::string + format_error( + const char * name_type, + const char * name, + const char * error_msg, + size_t invalid_index); + + const std::string name_type; + const std::string name; + const std::string error_msg; + const size_t invalid_index; +}; + +/// Thrown when a node name is invalid. +class InvalidNodeNameError : public NameValidationError +{ +public: + InvalidNodeNameError(const char * node_name, const char * error_msg, size_t invalid_index) + : NameValidationError("node name", node_name, error_msg, invalid_index) + {} +}; + +/// Thrown when a node namespace is invalid. +class InvalidNamespaceError : public NameValidationError +{ +public: + InvalidNamespaceError(const char * namespace_, const char * error_msg, size_t invalid_index) + : NameValidationError("namespace", namespace_, error_msg, invalid_index) + {} +}; + +/// Thrown when a topic name is invalid. +class InvalidTopicNameError : public NameValidationError +{ +public: + InvalidTopicNameError(const char * namespace_, const char * error_msg, size_t invalid_index) + : NameValidationError("topic name", namespace_, error_msg, invalid_index) + {} +}; + +/// Thrown when a service name is invalid. +class InvalidServiceNameError : public NameValidationError +{ +public: + InvalidServiceNameError(const char * namespace_, const char * error_msg, size_t invalid_index) + : NameValidationError("service name", namespace_, error_msg, invalid_index) + {} +}; + +/// Throw a C++ std::exception which was created based on an rcl error. +/** + * Passing nullptr for reset_error is safe and will avoid calling any function + * to reset the error. + * + * \param ret the return code for the current error state + * \param prefix string to prefix to the error if applicable (not all errors have custom messages) + * \param error_state error state to create exception from, if nullptr rcl_get_error_state is used + * \param reset_error function to be called before throwing which whill clear the error state + * \throws std::invalid_argument if ret is RCL_RET_OK + * \throws std::runtime_error if the rcl_get_error_state returns 0 + * \throws RCLErrorBase some child class exception based on ret + */ +/* *INDENT-OFF* */ // Uncrustify cannot yet understand [[noreturn]] properly +RCLCPP_PUBLIC +void +throw_from_rcl_error [[noreturn]] ( + rcl_ret_t ret, + const std::string & prefix = "", + const rcl_error_state_t * error_state = nullptr, + void (* reset_error)() = rcl_reset_error); +/* *INDENT-ON* */ + +class RCLErrorBase +{ +public: + RCLCPP_PUBLIC + RCLErrorBase(rcl_ret_t ret, const rcl_error_state_t * error_state); + virtual ~RCLErrorBase() {} + + rcl_ret_t ret; + std::string message; + std::string file; + size_t line; + std::string formatted_message; +}; + +/// Created when the return code does not match one of the other specialized exceptions. +class RCLError : public RCLErrorBase, public std::runtime_error +{ +public: + RCLCPP_PUBLIC + RCLError(rcl_ret_t ret, const rcl_error_state_t * error_state, const std::string & prefix); + RCLCPP_PUBLIC + RCLError(const RCLErrorBase & base_exc, const std::string & prefix); +}; + +/// Created when the ret is RCL_RET_BAD_ALLOC. +class RCLBadAlloc : public RCLErrorBase, public std::bad_alloc +{ +public: + RCLCPP_PUBLIC + RCLBadAlloc(rcl_ret_t ret, const rcl_error_state_t * error_state); + RCLCPP_PUBLIC + explicit RCLBadAlloc(const RCLErrorBase & base_exc); +}; + +/// Created when the ret is RCL_RET_INVALID_ARGUMENT. +class RCLInvalidArgument : public RCLErrorBase, public std::invalid_argument +{ +public: + RCLCPP_PUBLIC + RCLInvalidArgument( + rcl_ret_t ret, + const rcl_error_state_t * error_state, + const std::string & prefix); + RCLCPP_PUBLIC + RCLInvalidArgument(const RCLErrorBase & base_exc, const std::string & prefix); +}; + +/// Created when the ret is RCL_RET_INVALID_ROS_ARGS. +class RCLInvalidROSArgsError : public RCLErrorBase, public std::runtime_error +{ +public: + RCLCPP_PUBLIC + RCLInvalidROSArgsError( + rcl_ret_t ret, const rcl_error_state_t * error_state, const std::string & prefix); + RCLCPP_PUBLIC + RCLInvalidROSArgsError(const RCLErrorBase & base_exc, const std::string & prefix); +}; + +/// Thrown when unparsed ROS specific arguments are found. +class UnknownROSArgsError : public std::runtime_error +{ +public: + explicit UnknownROSArgsError(std::vector && unknown_ros_args_in) + : std::runtime_error( + "found unknown ROS arguments: '" + rcpputils::join(unknown_ros_args_in, "', '") + "'"), + unknown_ros_args(unknown_ros_args_in) + { + } + + const std::vector unknown_ros_args; +}; + +/// Thrown when an invalid rclcpp::Event object or SharedPtr is encountered. +class InvalidEventError : public std::runtime_error +{ +public: + InvalidEventError() + : std::runtime_error("event is invalid") {} +}; + +/// Thrown when an unregistered rclcpp::Event is encountered where a registered one was expected. +class EventNotRegisteredError : public std::runtime_error +{ +public: + EventNotRegisteredError() + : std::runtime_error("event already registered") {} +}; + +/// Thrown if passed parameters are inconsistent or invalid +class InvalidParametersException : public std::runtime_error +{ +public: + // Inherit constructors from runtime_error. + using std::runtime_error::runtime_error; +}; + +/// Thrown if passed parameter value is invalid. +class InvalidParameterValueException : public std::runtime_error +{ + // Inherit constructors from runtime_error. + using std::runtime_error::runtime_error; +}; + +/// Thrown if requested parameter type is invalid. +/** + * Essentially the same as rclcpp::ParameterTypeException, but with parameter + * name in the error message. + */ +class InvalidParameterTypeException : public std::runtime_error +{ +public: + /// Construct an instance. + /** + * \param[in] name the name of the parameter. + * \param[in] message custom exception message. + */ + RCLCPP_PUBLIC + InvalidParameterTypeException(const std::string & name, const std::string message) + : std::runtime_error("parameter '" + name + "' has invalid type: " + message) + {} +}; + +/// Thrown if parameter is already declared. +class ParameterAlreadyDeclaredException : public std::runtime_error +{ + // Inherit constructors from runtime_error. + using std::runtime_error::runtime_error; +}; + +/// Thrown if parameter is not declared, e.g. either set or get was called without first declaring. +class ParameterNotDeclaredException : public std::runtime_error +{ + // Inherit constructors from runtime_error. + using std::runtime_error::runtime_error; +}; + +/// Thrown if parameter is immutable and therefore cannot be undeclared. +class ParameterImmutableException : public std::runtime_error +{ + // Inherit constructors from runtime_error. + using std::runtime_error::runtime_error; +}; + +/// Thrown if parameter is modified while in a set callback. +class ParameterModifiedInCallbackException : public std::runtime_error +{ + // Inherit constructors from runtime_error. + using std::runtime_error::runtime_error; +}; + +} // namespace exceptions +} // namespace rclcpp + +#endif // RCLCPP__EXCEPTIONS__EXCEPTIONS_HPP_ diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index aa94c01476..4f71ae0052 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -30,6 +30,8 @@ #include "rcl/wait.h" #include "rclcpp/contexts/default_context.hpp" +#include "rclcpp/executor_options.hpp" +#include "rclcpp/future_return_code.hpp" #include "rclcpp/memory_strategies.hpp" #include "rclcpp/memory_strategy.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" @@ -42,48 +44,6 @@ namespace rclcpp // Forward declaration is used in convenience method signature. class Node; -namespace executor -{ - -/// Return codes to be used with spin_until_future_complete. -/** - * SUCCESS: The future is complete and can be accessed with "get" without blocking. - * This does not indicate that the operation succeeded; "get" may still throw an exception. - * INTERRUPTED: The future is not complete, spinning was interrupted by Ctrl-C or another error. - * TIMEOUT: Spinning timed out. - */ -enum class FutureReturnCode {SUCCESS, INTERRUPTED, TIMEOUT}; - -RCLCPP_PUBLIC -std::ostream & -operator<<(std::ostream & os, const FutureReturnCode & future_return_code); - -RCLCPP_PUBLIC -std::string -to_string(const FutureReturnCode & future_return_code); - -/// -/** - * Options to be passed to the executor constructor. - */ -struct ExecutorArgs -{ - ExecutorArgs() - : memory_strategy(memory_strategies::create_default_strategy()), - context(rclcpp::contexts::default_context::get_global_default_context()), - max_conditions(0) - {} - - memory_strategy::MemoryStrategy::SharedPtr memory_strategy; - std::shared_ptr context; - size_t max_conditions; -}; - -static inline ExecutorArgs create_default_executor_arguments() -{ - return ExecutorArgs(); -} - /// Coordinate the order and timing of available communication tasks. /** * Executor provides spin functions (including spin_node_once and spin_some). @@ -100,9 +60,11 @@ class Executor RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Executor) /// Default constructor. - // \param[in] ms The memory strategy to be used with this executor. + /** + * \param[in] options Options used to configure the executor. + */ RCLCPP_PUBLIC - explicit Executor(const ExecutorArgs & args = ExecutorArgs()); + explicit Executor(const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions()); /// Default destructor. RCLCPP_PUBLIC @@ -323,10 +285,10 @@ class Executor RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr - get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group); + get_node_by_group(rclcpp::CallbackGroup::SharedPtr group); RCLCPP_PUBLIC - rclcpp::callback_group::CallbackGroup::SharedPtr + rclcpp::CallbackGroup::SharedPtr get_group_by_timer(rclcpp::TimerBase::SharedPtr timer); RCLCPP_PUBLIC @@ -363,6 +325,11 @@ class Executor std::list guard_conditions_; }; +namespace executor +{ + +using Executor [[deprecated("use rclcpp::Executor instead")]] = rclcpp::Executor; + } // namespace executor } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/executor_options.hpp b/rclcpp/include/rclcpp/executor_options.hpp new file mode 100644 index 0000000000..d5ec6d0da9 --- /dev/null +++ b/rclcpp/include/rclcpp/executor_options.hpp @@ -0,0 +1,57 @@ +// Copyright 2014-2020 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__EXECUTOR_OPTIONS_HPP_ +#define RCLCPP__EXECUTOR_OPTIONS_HPP_ + +#include "rclcpp/context.hpp" +#include "rclcpp/contexts/default_context.hpp" +#include "rclcpp/memory_strategies.hpp" +#include "rclcpp/memory_strategy.hpp" +#include "rclcpp/visibility_control.hpp" + +namespace rclcpp +{ + +/// Options to be passed to the executor constructor. +struct ExecutorOptions +{ + ExecutorOptions() + : memory_strategy(rclcpp::memory_strategies::create_default_strategy()), + context(rclcpp::contexts::get_global_default_context()), + max_conditions(0) + {} + + rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy; + rclcpp::Context::SharedPtr context; + size_t max_conditions; +}; + +namespace executor +{ + +using ExecutorArgs [[deprecated("use rclcpp::ExecutorOptions instead")]] = ExecutorOptions; + +[[deprecated("use rclcpp::ExecutorOptions() instead")]] +inline +rclcpp::ExecutorOptions +create_default_executor_arguments() +{ + return rclcpp::ExecutorOptions(); +} + +} // namespace executor +} // namespace rclcpp + +#endif // RCLCPP__EXECUTOR_OPTIONS_HPP_ diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index ac91141a43..ec55d1309e 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -67,9 +67,9 @@ using rclcpp::executors::SingleThreadedExecutor; * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. */ template -rclcpp::executor::FutureReturnCode +rclcpp::FutureReturnCode spin_node_until_future_complete( - rclcpp::executor::Executor & executor, + rclcpp::Executor & executor, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const std::shared_future & future, std::chrono::duration timeout = std::chrono::duration(-1)) @@ -84,9 +84,9 @@ spin_node_until_future_complete( template -rclcpp::executor::FutureReturnCode +rclcpp::FutureReturnCode spin_node_until_future_complete( - rclcpp::executor::Executor & executor, + rclcpp::Executor & executor, std::shared_ptr node_ptr, const std::shared_future & future, std::chrono::duration timeout = std::chrono::duration(-1)) @@ -101,7 +101,7 @@ spin_node_until_future_complete( } // namespace executors template -rclcpp::executor::FutureReturnCode +rclcpp::FutureReturnCode spin_until_future_complete( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const std::shared_future & future, @@ -113,7 +113,7 @@ spin_until_future_complete( template -rclcpp::executor::FutureReturnCode +rclcpp::FutureReturnCode spin_until_future_complete( std::shared_ptr node_ptr, const std::shared_future & future, diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index fd9ad33cf0..7cc82c88db 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -32,7 +32,7 @@ namespace rclcpp namespace executors { -class MultiThreadedExecutor : public executor::Executor +class MultiThreadedExecutor : public rclcpp::Executor { public: RCLCPP_SMART_PTR_DEFINITIONS(MultiThreadedExecutor) @@ -45,14 +45,14 @@ class MultiThreadedExecutor : public executor::Executor * This is useful for reproducing some bugs related to taking work more than * once. * - * \param args common arguments for all executors + * \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 * \param yield_before_execute if true std::this_thread::yield() is called */ RCLCPP_PUBLIC MultiThreadedExecutor( - const executor::ExecutorArgs & args = executor::ExecutorArgs(), + const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions(), size_t number_of_threads = 0, bool yield_before_execute = false, std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); diff --git a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp index 523c2e5657..be1310f8df 100644 --- a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp @@ -35,25 +35,31 @@ namespace rclcpp namespace executors { -/// Single-threaded executor implementation -// This is the default executor created by rclcpp::spin. -class SingleThreadedExecutor : public executor::Executor +/// Single-threaded executor implementation. +/** + * This is the default executor created by rclcpp::spin. + */ +class SingleThreadedExecutor : public rclcpp::Executor { public: RCLCPP_SMART_PTR_DEFINITIONS(SingleThreadedExecutor) /// Default constructor. See the default constructor for Executor. RCLCPP_PUBLIC - SingleThreadedExecutor( - const executor::ExecutorArgs & args = executor::ExecutorArgs()); + explicit SingleThreadedExecutor( + const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions()); - /// Default destrcutor. + /// Default destructor. RCLCPP_PUBLIC virtual ~SingleThreadedExecutor(); /// Single-threaded implementation of spin. - // This function will block until work comes in, execute it, and keep blocking. - // It will only be interrupt by a CTRL-C (managed by the global signal handler). + /** + * This function will block until work comes in, execute it, and then repeat + * the process until canceled. + * It may be interrupt by a call to rclcpp::Executor::cancel() or by ctrl-c + * if the associated context is configured to shutdown on SIGINT. + */ RCLCPP_PUBLIC void spin() override; diff --git a/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp b/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp index c2792afae6..f9a0525112 100644 --- a/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp +++ b/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp @@ -22,7 +22,7 @@ #include "rcl/guard_condition.h" #include "rcl/wait.h" -#include "rclcpp/executable_list.hpp" +#include "rclcpp/experimental/executable_list.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/memory_strategy.hpp" #include "rclcpp/visibility_control.hpp" @@ -159,7 +159,7 @@ class StaticExecutorEntitiesCollector final rcl_wait_set_t * p_wait_set_ = nullptr; /// Executable list: timers, subscribers, clients, services and waitables - rclcpp::executor::ExecutableList exec_list_; + rclcpp::experimental::ExecutableList exec_list_; }; } // namespace executors diff --git a/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp index 43d086f7db..bf68985812 100644 --- a/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp @@ -23,9 +23,9 @@ #include "rmw/rmw.h" -#include "rclcpp/executable_list.hpp" #include "rclcpp/executor.hpp" #include "rclcpp/executors/static_executor_entities_collector.hpp" +#include "rclcpp/experimental/executable_list.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/memory_strategies.hpp" #include "rclcpp/node.hpp" @@ -54,7 +54,7 @@ namespace executors * exec.spin(); * exec.remove_node(node); */ -class StaticSingleThreadedExecutor : public executor::Executor +class StaticSingleThreadedExecutor : public rclcpp::Executor { public: RCLCPP_SMART_PTR_DEFINITIONS(StaticSingleThreadedExecutor) @@ -62,7 +62,7 @@ class StaticSingleThreadedExecutor : public executor::Executor /// Default constructor. See the default constructor for Executor. RCLCPP_PUBLIC explicit StaticSingleThreadedExecutor( - const executor::ExecutorArgs & args = executor::ExecutorArgs()); + const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions()); /// Default destrcutor. RCLCPP_PUBLIC @@ -131,14 +131,14 @@ class StaticSingleThreadedExecutor : public executor::Executor * exec.spin_until_future_complete(future); */ template - rclcpp::executor::FutureReturnCode + rclcpp::FutureReturnCode spin_until_future_complete( std::shared_future & future, std::chrono::duration timeout = std::chrono::duration(-1)) { std::future_status status = future.wait_for(std::chrono::seconds(0)); if (status == std::future_status::ready) { - return rclcpp::executor::FutureReturnCode::SUCCESS; + return rclcpp::FutureReturnCode::SUCCESS; } auto end_time = std::chrono::steady_clock::now(); @@ -159,7 +159,7 @@ class StaticSingleThreadedExecutor : public executor::Executor // Check if the future is set, return SUCCESS if it is. status = future.wait_for(std::chrono::seconds(0)); if (status == std::future_status::ready) { - return rclcpp::executor::FutureReturnCode::SUCCESS; + return rclcpp::FutureReturnCode::SUCCESS; } // If the original timeout is < 0, then this is blocking, never TIMEOUT. if (timeout_ns < std::chrono::nanoseconds::zero()) { @@ -168,14 +168,14 @@ class StaticSingleThreadedExecutor : public executor::Executor // Otherwise check if we still have time to wait, return TIMEOUT if not. auto now = std::chrono::steady_clock::now(); if (now >= end_time) { - return rclcpp::executor::FutureReturnCode::TIMEOUT; + return rclcpp::FutureReturnCode::TIMEOUT; } // Subtract the elapsed time from the original timeout. timeout_left = std::chrono::duration_cast(end_time - now); } // The future did not complete before ok() returned false, return INTERRUPTED. - return rclcpp::executor::FutureReturnCode::INTERRUPTED; + return rclcpp::FutureReturnCode::INTERRUPTED; } protected: diff --git a/rclcpp/include/rclcpp/executable_list.hpp b/rclcpp/include/rclcpp/experimental/executable_list.hpp similarity index 92% rename from rclcpp/include/rclcpp/executable_list.hpp rename to rclcpp/include/rclcpp/experimental/executable_list.hpp index 2929b5410a..e1c70db3de 100644 --- a/rclcpp/include/rclcpp/executable_list.hpp +++ b/rclcpp/include/rclcpp/experimental/executable_list.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef RCLCPP__EXECUTABLE_LIST_HPP_ -#define RCLCPP__EXECUTABLE_LIST_HPP_ +#ifndef RCLCPP__EXPERIMENTAL__EXECUTABLE_LIST_HPP_ +#define RCLCPP__EXPERIMENTAL__EXECUTABLE_LIST_HPP_ #include #include @@ -27,7 +27,7 @@ namespace rclcpp { -namespace executor +namespace experimental { /// This class contains subscriptionbase, timerbase, etc. which can be used to run callbacks. @@ -86,7 +86,7 @@ class ExecutableList final size_t number_of_waitables; }; -} // namespace executor +} // namespace experimental } // namespace rclcpp -#endif // RCLCPP__EXECUTABLE_LIST_HPP_ +#endif // RCLCPP__EXPERIMENTAL__EXECUTABLE_LIST_HPP_ diff --git a/rclcpp/include/rclcpp/future_return_code.hpp b/rclcpp/include/rclcpp/future_return_code.hpp new file mode 100644 index 0000000000..9161fa832d --- /dev/null +++ b/rclcpp/include/rclcpp/future_return_code.hpp @@ -0,0 +1,61 @@ +// Copyright 2014 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__FUTURE_RETURN_CODE_HPP_ +#define RCLCPP__FUTURE_RETURN_CODE_HPP_ + +#include +#include + +#include "rclcpp/visibility_control.hpp" + +namespace rclcpp +{ + +/// Return codes to be used with spin_until_future_complete. +/** + * SUCCESS: The future is complete and can be accessed with "get" without blocking. + * This does not indicate that the operation succeeded; "get" may still throw an exception. + * INTERRUPTED: The future is not complete, spinning was interrupted by Ctrl-C or another error. + * TIMEOUT: Spinning timed out. + */ +enum class FutureReturnCode {SUCCESS, INTERRUPTED, TIMEOUT}; + +/// Stream operator for FutureReturnCode. +RCLCPP_PUBLIC +std::ostream & +operator<<(std::ostream & os, const FutureReturnCode & future_return_code); + +/// String conversion function for FutureReturnCode. +RCLCPP_PUBLIC +std::string +to_string(const FutureReturnCode & future_return_code); + +namespace executor +{ + +using FutureReturnCode [[deprecated("use rclcpp::FutureReturnCode instead")]] = FutureReturnCode; + +[[deprecated("use rclcpp::to_string(const rclcpp::FutureReturnCode &) instead")]] +inline +std::string +to_string(const rclcpp::FutureReturnCode & future_return_code) +{ + return rclcpp::to_string(future_return_code); +} + +} // namespace executor +} // namespace rclcpp + +#endif // RCLCPP__FUTURE_RETURN_CODE_HPP_ diff --git a/rclcpp/include/rclcpp/guard_condition.hpp b/rclcpp/include/rclcpp/guard_condition.hpp index 5088181022..010c127a07 100644 --- a/rclcpp/include/rclcpp/guard_condition.hpp +++ b/rclcpp/include/rclcpp/guard_condition.hpp @@ -47,7 +47,7 @@ class GuardCondition RCLCPP_PUBLIC explicit GuardCondition( rclcpp::Context::SharedPtr context = - rclcpp::contexts::default_context::get_global_default_context()); + rclcpp::contexts::get_global_default_context()); RCLCPP_PUBLIC virtual diff --git a/rclcpp/include/rclcpp/memory_strategy.hpp b/rclcpp/include/rclcpp/memory_strategy.hpp index 3549802bdd..5677533a4a 100644 --- a/rclcpp/include/rclcpp/memory_strategy.hpp +++ b/rclcpp/include/rclcpp/memory_strategy.hpp @@ -67,27 +67,27 @@ class RCLCPP_PUBLIC MemoryStrategy virtual void get_next_subscription( - rclcpp::executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) = 0; virtual void get_next_service( - rclcpp::executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) = 0; virtual void get_next_client( - rclcpp::executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) = 0; virtual void get_next_timer( - rclcpp::executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) = 0; virtual void get_next_waitable( - rclcpp::executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) = 0; virtual rcl_allocator_t @@ -115,30 +115,30 @@ class RCLCPP_PUBLIC MemoryStrategy static rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_by_group( - rclcpp::callback_group::CallbackGroup::SharedPtr group, + rclcpp::CallbackGroup::SharedPtr group, const WeakNodeList & weak_nodes); - static rclcpp::callback_group::CallbackGroup::SharedPtr + static rclcpp::CallbackGroup::SharedPtr get_group_by_subscription( rclcpp::SubscriptionBase::SharedPtr subscription, const WeakNodeList & weak_nodes); - static rclcpp::callback_group::CallbackGroup::SharedPtr + static rclcpp::CallbackGroup::SharedPtr get_group_by_service( rclcpp::ServiceBase::SharedPtr service, const WeakNodeList & weak_nodes); - static rclcpp::callback_group::CallbackGroup::SharedPtr + static rclcpp::CallbackGroup::SharedPtr get_group_by_client( rclcpp::ClientBase::SharedPtr client, const WeakNodeList & weak_nodes); - static rclcpp::callback_group::CallbackGroup::SharedPtr + static rclcpp::CallbackGroup::SharedPtr get_group_by_timer( rclcpp::TimerBase::SharedPtr timer, const WeakNodeList & weak_nodes); - static rclcpp::callback_group::CallbackGroup::SharedPtr + static rclcpp::CallbackGroup::SharedPtr get_group_by_waitable( rclcpp::Waitable::SharedPtr waitable, const WeakNodeList & weak_nodes); diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 43e3a94fdc..6131fef95a 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -135,12 +135,12 @@ class Node : public std::enable_shared_from_this /// Create and return a callback group. RCLCPP_PUBLIC - rclcpp::callback_group::CallbackGroup::SharedPtr - create_callback_group(rclcpp::callback_group::CallbackGroupType group_type); + rclcpp::CallbackGroup::SharedPtr + create_callback_group(rclcpp::CallbackGroupType group_type); /// Return the list of callback groups in the node. RCLCPP_PUBLIC - const std::vector & + const std::vector & get_callback_groups() const; /// Create and return a Publisher. @@ -227,7 +227,7 @@ class Node : public std::enable_shared_from_this create_wall_timer( std::chrono::duration period, CallbackT callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); /* Create and return a Client. */ template @@ -235,7 +235,7 @@ class Node : public std::enable_shared_from_this create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); /* Create and return a Service. */ template @@ -244,7 +244,7 @@ class Node : public std::enable_shared_from_this const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Declare and initialize a parameter, return the effective value. /** @@ -1142,7 +1142,7 @@ class Node : public std::enable_shared_from_this RCLCPP_PUBLIC bool - group_in_node(callback_group::CallbackGroup::SharedPtr group); + group_in_node(CallbackGroup::SharedPtr group); rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_; rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_; diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 512f472f79..4a24d0d359 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -109,7 +109,7 @@ typename rclcpp::WallTimer::SharedPtr Node::create_wall_timer( std::chrono::duration period, CallbackT callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_wall_timer( period, @@ -124,7 +124,7 @@ typename Client::SharedPtr Node::create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_client( node_base_, @@ -141,7 +141,7 @@ Node::create_service( const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_service( node_base_, diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp index c21514ff97..73861df680 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp @@ -96,22 +96,22 @@ class NodeBase : public NodeBaseInterface RCLCPP_PUBLIC - rclcpp::callback_group::CallbackGroup::SharedPtr - create_callback_group(rclcpp::callback_group::CallbackGroupType group_type) override; + rclcpp::CallbackGroup::SharedPtr + create_callback_group(rclcpp::CallbackGroupType group_type) override; RCLCPP_PUBLIC - rclcpp::callback_group::CallbackGroup::SharedPtr + rclcpp::CallbackGroup::SharedPtr get_default_callback_group() override; RCLCPP_PUBLIC bool - callback_group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group) override; + callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) override; RCLCPP_PUBLIC - const std::vector & + const std::vector & get_callback_groups() const override; RCLCPP_PUBLIC @@ -146,8 +146,8 @@ class NodeBase : public NodeBaseInterface std::shared_ptr node_handle_; - rclcpp::callback_group::CallbackGroup::SharedPtr default_callback_group_; - std::vector callback_groups_; + rclcpp::CallbackGroup::SharedPtr default_callback_group_; + std::vector callback_groups_; std::atomic_bool associated_with_executor_; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp index eb7d34d81c..33e4ee3462 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp @@ -111,25 +111,25 @@ class NodeBaseInterface /// Create and return a callback group. RCLCPP_PUBLIC virtual - rclcpp::callback_group::CallbackGroup::SharedPtr - create_callback_group(rclcpp::callback_group::CallbackGroupType group_type) = 0; + rclcpp::CallbackGroup::SharedPtr + create_callback_group(rclcpp::CallbackGroupType group_type) = 0; /// Return the default callback group. RCLCPP_PUBLIC virtual - rclcpp::callback_group::CallbackGroup::SharedPtr + rclcpp::CallbackGroup::SharedPtr get_default_callback_group() = 0; /// Return true if the given callback group is associated with this node. RCLCPP_PUBLIC virtual bool - callback_group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group) = 0; + callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) = 0; /// Return list of callback groups associated with this node. RCLCPP_PUBLIC virtual - const std::vector & + const std::vector & get_callback_groups() const = 0; /// Return the atomic bool which is used to ensure only one executor is used. diff --git a/rclcpp/include/rclcpp/node_interfaces/node_services.hpp b/rclcpp/include/rclcpp/node_interfaces/node_services.hpp index 416fb32c7e..01c9912344 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_services.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_services.hpp @@ -46,14 +46,14 @@ class NodeServices : public NodeServicesInterface void add_client( rclcpp::ClientBase::SharedPtr client_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) override; + rclcpp::CallbackGroup::SharedPtr group) override; RCLCPP_PUBLIC void add_service( rclcpp::ServiceBase::SharedPtr service_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) override; + rclcpp::CallbackGroup::SharedPtr group) override; private: RCLCPP_DISABLE_COPY(NodeServices) diff --git a/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp index c75fec865f..53a2e3fc4c 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_services_interface.hpp @@ -41,14 +41,14 @@ class NodeServicesInterface void add_client( rclcpp::ClientBase::SharedPtr client_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) = 0; + rclcpp::CallbackGroup::SharedPtr group) = 0; RCLCPP_PUBLIC virtual void add_service( rclcpp::ServiceBase::SharedPtr service_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) = 0; + rclcpp::CallbackGroup::SharedPtr group) = 0; }; } // namespace node_interfaces diff --git a/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp b/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp index 27e2292dbe..03f151ff25 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_timers.hpp @@ -46,7 +46,7 @@ class NodeTimers : public NodeTimersInterface void add_timer( rclcpp::TimerBase::SharedPtr timer, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) override; + rclcpp::CallbackGroup::SharedPtr callback_group) override; private: RCLCPP_DISABLE_COPY(NodeTimers) diff --git a/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp index 422409af57..4573d3d02b 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_timers_interface.hpp @@ -41,7 +41,7 @@ class NodeTimersInterface void add_timer( rclcpp::TimerBase::SharedPtr timer, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) = 0; + rclcpp::CallbackGroup::SharedPtr callback_group) = 0; }; } // namespace node_interfaces diff --git a/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp b/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp index 227d193516..38402eff6e 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_topics.hpp @@ -58,7 +58,7 @@ class NodeTopics : public NodeTopicsInterface void add_publisher( rclcpp::PublisherBase::SharedPtr publisher, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) override; + rclcpp::CallbackGroup::SharedPtr callback_group) override; RCLCPP_PUBLIC rclcpp::SubscriptionBase::SharedPtr @@ -71,7 +71,7 @@ class NodeTopics : public NodeTopicsInterface void add_subscription( rclcpp::SubscriptionBase::SharedPtr subscription, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) override; + rclcpp::CallbackGroup::SharedPtr callback_group) override; RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface * diff --git a/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp index 4ba28d5e40..4d9edd0b18 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp @@ -60,7 +60,7 @@ class NodeTopicsInterface void add_publisher( rclcpp::PublisherBase::SharedPtr publisher, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) = 0; + rclcpp::CallbackGroup::SharedPtr callback_group) = 0; RCLCPP_PUBLIC virtual @@ -75,7 +75,7 @@ class NodeTopicsInterface void add_subscription( rclcpp::SubscriptionBase::SharedPtr subscription, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) = 0; + rclcpp::CallbackGroup::SharedPtr callback_group) = 0; RCLCPP_PUBLIC virtual diff --git a/rclcpp/include/rclcpp/node_interfaces/node_waitables.hpp b/rclcpp/include/rclcpp/node_interfaces/node_waitables.hpp index c0b5719a02..fd560bca48 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_waitables.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_waitables.hpp @@ -45,14 +45,14 @@ class NodeWaitables : public NodeWaitablesInterface void add_waitable( rclcpp::Waitable::SharedPtr waitable_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) override; + rclcpp::CallbackGroup::SharedPtr group) override; RCLCPP_PUBLIC void remove_waitable( rclcpp::Waitable::SharedPtr waitable_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) noexcept override; + rclcpp::CallbackGroup::SharedPtr group) noexcept override; private: RCLCPP_DISABLE_COPY(NodeWaitables) diff --git a/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp index e848cea286..0faae1da62 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_waitables_interface.hpp @@ -40,7 +40,7 @@ class NodeWaitablesInterface void add_waitable( rclcpp::Waitable::SharedPtr waitable_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) = 0; + rclcpp::CallbackGroup::SharedPtr group) = 0; /// \note this function should not throw because it may be called in destructors RCLCPP_PUBLIC @@ -48,7 +48,7 @@ class NodeWaitablesInterface void remove_waitable( rclcpp::Waitable::SharedPtr waitable_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) noexcept = 0; + rclcpp::CallbackGroup::SharedPtr group) noexcept = 0; }; } // namespace node_interfaces diff --git a/rclcpp/include/rclcpp/node_options.hpp b/rclcpp/include/rclcpp/node_options.hpp index c13789598f..32464c556c 100644 --- a/rclcpp/include/rclcpp/node_options.hpp +++ b/rclcpp/include/rclcpp/node_options.hpp @@ -38,7 +38,7 @@ class NodeOptions /** * Default values for the node options: * - * - context = rclcpp::contexts::default_context::get_global_default_context() + * - context = rclcpp::contexts::get_global_default_context() * - arguments = {} * - parameter_overrides = {} * - use_global_arguments = true @@ -338,7 +338,7 @@ class NodeOptions // documentation in this class. rclcpp::Context::SharedPtr context_ { - rclcpp::contexts::default_context::get_global_default_context()}; + rclcpp::contexts::get_global_default_context()}; std::vector arguments_ {}; diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 73053617dc..021ceb37bd 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -54,21 +54,21 @@ class AsyncParametersClient 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, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); RCLCPP_PUBLIC AsyncParametersClient( const rclcpp::Node::SharedPtr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); RCLCPP_PUBLIC AsyncParametersClient( rclcpp::Node * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); RCLCPP_PUBLIC std::shared_future> @@ -205,7 +205,7 @@ class SyncParametersClient RCLCPP_PUBLIC SyncParametersClient( - rclcpp::executor::Executor::SharedPtr executor, + rclcpp::Executor::SharedPtr executor, rclcpp::Node::SharedPtr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); @@ -218,14 +218,14 @@ class SyncParametersClient RCLCPP_PUBLIC SyncParametersClient( - rclcpp::executor::Executor::SharedPtr executor, + rclcpp::Executor::SharedPtr executor, rclcpp::Node * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); RCLCPP_PUBLIC SyncParametersClient( - rclcpp::executor::Executor::SharedPtr executor, + 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, @@ -339,7 +339,7 @@ class SyncParametersClient } private: - rclcpp::executor::Executor::SharedPtr executor_; + rclcpp::Executor::SharedPtr executor_; const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_; AsyncParametersClient::SharedPtr async_parameters_client_; }; diff --git a/rclcpp/include/rclcpp/publisher_options.hpp b/rclcpp/include/rclcpp/publisher_options.hpp index 75d0e69b9f..dd24718fd7 100644 --- a/rclcpp/include/rclcpp/publisher_options.hpp +++ b/rclcpp/include/rclcpp/publisher_options.hpp @@ -30,10 +30,7 @@ namespace rclcpp { -namespace callback_group -{ class CallbackGroup; -} // namespace callback_group /// Non-templated part of PublisherOptionsWithAllocator. struct PublisherOptionsBase @@ -48,7 +45,7 @@ struct PublisherOptionsBase bool use_default_callbacks = true; /// Callback group in which the waitable items from the publisher should be placed. - std::shared_ptr callback_group; + std::shared_ptr callback_group; /// Optional RMW implementation specific payload to be used during creation of the publisher. std::shared_ptr diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index fc7b4435a4..556085ee07 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -81,7 +81,7 @@ * - rclcpp/executors/multi_threaded_executor.hpp * - CallbackGroups (mechanism for enforcing concurrency rules for callbacks): * - rclcpp::Node::create_callback_group() - * - rclcpp::callback_group::CallbackGroup + * - rclcpp::CallbackGroup * - rclcpp/callback_group.hpp * * Additionally, there are some methods for introspecting the ROS graph: diff --git a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp index bffd3995a6..4cad8d548b 100644 --- a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp @@ -263,7 +263,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy void get_next_subscription( - executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override { auto it = subscription_handles_.begin(); @@ -298,7 +298,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy void get_next_service( - executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override { auto it = service_handles_.begin(); @@ -332,7 +332,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy } void - get_next_client(executor::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override + get_next_client(rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override { auto it = client_handles_.begin(); while (it != client_handles_.end()) { @@ -366,7 +366,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy void get_next_timer( - executor::AnyExecutable & any_exec, + rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override { auto it = timer_handles_.begin(); @@ -400,7 +400,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy } void - get_next_waitable(executor::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override + get_next_waitable(rclcpp::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) override { auto it = waitable_handles_.begin(); while (it != waitable_handles_.end()) { diff --git a/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp b/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp index 0eb1d54b92..0e7d4366e5 100644 --- a/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp @@ -17,6 +17,8 @@ #include +#include "rosidl_runtime_cpp/traits.hpp" + #include "rclcpp/macros.hpp" #include "rclcpp/message_memory_strategy.hpp" #include "rclcpp/visibility_control.hpp" diff --git a/rclcpp/include/rclcpp/subscription_options.hpp b/rclcpp/include/rclcpp/subscription_options.hpp index e631ba5da2..12275d74fe 100644 --- a/rclcpp/include/rclcpp/subscription_options.hpp +++ b/rclcpp/include/rclcpp/subscription_options.hpp @@ -45,7 +45,7 @@ struct SubscriptionOptionsBase bool ignore_local_publications = false; /// The callback group for this subscription. NULL to use the default callback group. - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group = nullptr; + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr; /// Setting to explicitly set intraprocess communications. IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault; diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index 690df026bc..d876b2d1d9 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -45,7 +45,7 @@ namespace rclcpp /// Initialize communications via the rmw implementation and set up a global signal handler. /** * Initializes the global context which is accessible via the function - * rclcpp::contexts::default_context::get_global_default_context(). + * rclcpp::contexts::get_global_default_context(). * Also, installs the global signal handlers with the function * rclcpp::install_signal_handlers(). * diff --git a/rclcpp/include/rclcpp/wait_set_template.hpp b/rclcpp/include/rclcpp/wait_set_template.hpp index 899d461ed3..1c9b072275 100644 --- a/rclcpp/include/rclcpp/wait_set_template.hpp +++ b/rclcpp/include/rclcpp/wait_set_template.hpp @@ -74,7 +74,7 @@ class WaitSetTemplate final : private SynchronizationPolicy, private StoragePoli const typename StoragePolicy::ServicesIterable & services = {}, const typename StoragePolicy::WaitablesIterable & waitables = {}, rclcpp::Context::SharedPtr context = - rclcpp::contexts::default_context::get_global_default_context()) + rclcpp::contexts::get_global_default_context()) : SynchronizationPolicy(context), StoragePolicy( subscriptions, diff --git a/rclcpp/src/rclcpp/any_executable.cpp b/rclcpp/src/rclcpp/any_executable.cpp index e02d10701d..769deacb11 100644 --- a/rclcpp/src/rclcpp/any_executable.cpp +++ b/rclcpp/src/rclcpp/any_executable.cpp @@ -14,7 +14,7 @@ #include "rclcpp/any_executable.hpp" -using rclcpp::executor::AnyExecutable; +using rclcpp::AnyExecutable; AnyExecutable::AnyExecutable() : subscription(nullptr), diff --git a/rclcpp/src/rclcpp/callback_group.cpp b/rclcpp/src/rclcpp/callback_group.cpp index e9d0e80c48..db77e46b1e 100644 --- a/rclcpp/src/rclcpp/callback_group.cpp +++ b/rclcpp/src/rclcpp/callback_group.cpp @@ -16,8 +16,8 @@ #include -using rclcpp::callback_group::CallbackGroup; -using rclcpp::callback_group::CallbackGroupType; +using rclcpp::CallbackGroup; +using rclcpp::CallbackGroupType; CallbackGroup::CallbackGroup(CallbackGroupType group_type) : type_(group_type), can_be_taken_from_(true) diff --git a/rclcpp/src/rclcpp/contexts/default_context.cpp b/rclcpp/src/rclcpp/contexts/default_context.cpp index 53c6c9f3f2..3ece873db9 100644 --- a/rclcpp/src/rclcpp/contexts/default_context.cpp +++ b/rclcpp/src/rclcpp/contexts/default_context.cpp @@ -14,13 +14,13 @@ #include "rclcpp/contexts/default_context.hpp" -using rclcpp::contexts::default_context::DefaultContext; +using rclcpp::contexts::DefaultContext; DefaultContext::DefaultContext() {} DefaultContext::SharedPtr -rclcpp::contexts::default_context::get_global_default_context() +rclcpp::contexts::get_global_default_context() { static DefaultContext::SharedPtr default_context = DefaultContext::make_shared(); return default_context; diff --git a/rclcpp/src/rclcpp/exceptions.cpp b/rclcpp/src/rclcpp/exceptions/exceptions.cpp similarity index 100% rename from rclcpp/src/rclcpp/exceptions.cpp rename to rclcpp/src/rclcpp/exceptions/exceptions.cpp diff --git a/rclcpp/src/rclcpp/executable_list.cpp b/rclcpp/src/rclcpp/executable_list.cpp index d9dae57cdd..07edbc9586 100644 --- a/rclcpp/src/rclcpp/executable_list.cpp +++ b/rclcpp/src/rclcpp/executable_list.cpp @@ -14,9 +14,9 @@ #include -#include "rclcpp/executable_list.hpp" +#include "rclcpp/experimental/executable_list.hpp" -using rclcpp::executor::ExecutableList; +using rclcpp::experimental::ExecutableList; ExecutableList::ExecutableList() : number_of_subscriptions(0), diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index c25b47db49..2ef663baac 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -29,18 +29,18 @@ #include "rcutils/logging_macros.h" using rclcpp::exceptions::throw_from_rcl_error; -using rclcpp::executor::AnyExecutable; -using rclcpp::executor::Executor; -using rclcpp::executor::ExecutorArgs; -using rclcpp::executor::FutureReturnCode; +using rclcpp::AnyExecutable; +using rclcpp::Executor; +using rclcpp::ExecutorOptions; +using rclcpp::FutureReturnCode; -Executor::Executor(const ExecutorArgs & args) +Executor::Executor(const rclcpp::ExecutorOptions & options) : spinning(false), - memory_strategy_(args.memory_strategy) + memory_strategy_(options.memory_strategy) { rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options(); rcl_ret_t ret = rcl_guard_condition_init( - &interrupt_guard_condition_, args.context->get_rcl_context().get(), guard_condition_options); + &interrupt_guard_condition_, options.context->get_rcl_context().get(), guard_condition_options); if (RCL_RET_OK != ret) { throw_from_rcl_error(ret, "Failed to create interrupt guard condition in Executor constructor"); } @@ -49,14 +49,14 @@ Executor::Executor(const ExecutorArgs & args) // and one for the executor's guard cond (interrupt_guard_condition_) // Put the global ctrl-c guard condition in - memory_strategy_->add_guard_condition(args.context->get_interrupt_guard_condition(&wait_set_)); + memory_strategy_->add_guard_condition(options.context->get_interrupt_guard_condition(&wait_set_)); // Put the executor's guard condition in memory_strategy_->add_guard_condition(&interrupt_guard_condition_); rcl_allocator_t allocator = memory_strategy_->get_allocator(); // Store the context for later use. - context_ = args.context; + context_ = options.context; ret = rcl_wait_set_init( &wait_set_, @@ -502,7 +502,7 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout) } rclcpp::node_interfaces::NodeBaseInterface::SharedPtr -Executor::get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group) +Executor::get_node_by_group(rclcpp::CallbackGroup::SharedPtr group) { if (!group) { return nullptr; @@ -522,7 +522,7 @@ Executor::get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr gro return nullptr; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr Executor::get_group_by_timer(rclcpp::TimerBase::SharedPtr timer) { for (auto & weak_node : weak_nodes_) { @@ -544,7 +544,7 @@ Executor::get_group_by_timer(rclcpp::TimerBase::SharedPtr timer) } } } - return rclcpp::callback_group::CallbackGroup::SharedPtr(); + return rclcpp::CallbackGroup::SharedPtr(); } bool @@ -625,29 +625,3 @@ Executor::get_next_executable(AnyExecutable & any_executable, std::chrono::nanos } return success; } - -std::ostream & -rclcpp::executor::operator<<(std::ostream & os, const FutureReturnCode & future_return_code) -{ - return os << to_string(future_return_code); -} - -std::string -rclcpp::executor::to_string(const FutureReturnCode & future_return_code) -{ - using enum_type = std::underlying_type::type; - std::string prefix = "Unknown enum value ("; - std::string ret_as_string = std::to_string(static_cast(future_return_code)); - switch (future_return_code) { - case FutureReturnCode::SUCCESS: - prefix = "SUCCESS ("; - break; - case FutureReturnCode::INTERRUPTED: - prefix = "INTERRUPTED ("; - break; - case FutureReturnCode::TIMEOUT: - prefix = "TIMEOUT ("; - break; - } - return prefix + ret_as_string + ")"; -} diff --git a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp index e2f878abc7..0dfdc35467 100644 --- a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp @@ -25,11 +25,11 @@ using rclcpp::executors::MultiThreadedExecutor; MultiThreadedExecutor::MultiThreadedExecutor( - const rclcpp::executor::ExecutorArgs & args, + const rclcpp::ExecutorOptions & options, size_t number_of_threads, bool yield_before_execute, std::chrono::nanoseconds next_exec_timeout) -: executor::Executor(args), +: rclcpp::Executor(options), yield_before_execute_(yield_before_execute), next_exec_timeout_(next_exec_timeout) { @@ -74,7 +74,7 @@ void MultiThreadedExecutor::run(size_t) { while (rclcpp::ok(this->context_) && spinning.load()) { - executor::AnyExecutable any_exec; + rclcpp::AnyExecutable any_exec; { std::lock_guard wait_lock(wait_mutex_); if (!rclcpp::ok(this->context_) || !spinning.load()) { diff --git a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp index 7f699d81ae..360574f7a1 100644 --- a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp @@ -18,8 +18,8 @@ using rclcpp::executors::SingleThreadedExecutor; -SingleThreadedExecutor::SingleThreadedExecutor(const rclcpp::executor::ExecutorArgs & args) -: executor::Executor(args) {} +SingleThreadedExecutor::SingleThreadedExecutor(const rclcpp::ExecutorOptions & options) +: rclcpp::Executor(options) {} SingleThreadedExecutor::~SingleThreadedExecutor() {} @@ -31,7 +31,7 @@ SingleThreadedExecutor::spin() } RCLCPP_SCOPE_EXIT(this->spinning.store(false); ); while (rclcpp::ok(this->context_) && spinning.load()) { - rclcpp::executor::AnyExecutable any_executable; + rclcpp::AnyExecutable any_executable; if (get_next_executable(any_executable)) { execute_any_executable(any_executable); } diff --git a/rclcpp/src/rclcpp/executors/static_executor_entities_collector.cpp b/rclcpp/src/rclcpp/executors/static_executor_entities_collector.cpp index 0c08e849df..5461e665ab 100644 --- a/rclcpp/src/rclcpp/executors/static_executor_entities_collector.cpp +++ b/rclcpp/src/rclcpp/executors/static_executor_entities_collector.cpp @@ -46,7 +46,7 @@ StaticExecutorEntitiesCollector::init( rcl_guard_condition_t * executor_guard_condition) { // Empty initialize executable list - exec_list_ = executor::ExecutableList(); + exec_list_ = rclcpp::experimental::ExecutableList(); // Get executor's wait_set_ pointer p_wait_set_ = p_wait_set; // Get executor's memory strategy ptr diff --git a/rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp index c6c1d1be9c..728a0902a1 100644 --- a/rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp +++ b/rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp @@ -19,11 +19,11 @@ #include "rclcpp/scope_exit.hpp" using rclcpp::executors::StaticSingleThreadedExecutor; -using rclcpp::executor::ExecutableList; +using rclcpp::experimental::ExecutableList; StaticSingleThreadedExecutor::StaticSingleThreadedExecutor( - const rclcpp::executor::ExecutorArgs & args) -: executor::Executor(args) + const rclcpp::ExecutorOptions & options) +: rclcpp::Executor(options) { entities_collector_ = std::make_shared(); } diff --git a/rclcpp/src/rclcpp/future_return_code.cpp b/rclcpp/src/rclcpp/future_return_code.cpp new file mode 100644 index 0000000000..61e167dfb9 --- /dev/null +++ b/rclcpp/src/rclcpp/future_return_code.cpp @@ -0,0 +1,50 @@ +// Copyright 2015 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 "rclcpp/future_return_code.hpp" + +namespace rclcpp +{ + +std::ostream & +operator<<(std::ostream & os, const rclcpp::FutureReturnCode & future_return_code) +{ + return os << to_string(future_return_code); +} + +std::string +to_string(const rclcpp::FutureReturnCode & future_return_code) +{ + using enum_type = std::underlying_type::type; + std::string prefix = "Unknown enum value ("; + std::string ret_as_string = std::to_string(static_cast(future_return_code)); + switch (future_return_code) { + case FutureReturnCode::SUCCESS: + prefix = "SUCCESS ("; + break; + case FutureReturnCode::INTERRUPTED: + prefix = "INTERRUPTED ("; + break; + case FutureReturnCode::TIMEOUT: + prefix = "TIMEOUT ("; + break; + } + return prefix + ret_as_string + ")"; +} + +} // namespace rclcpp diff --git a/rclcpp/src/rclcpp/memory_strategy.cpp b/rclcpp/src/rclcpp/memory_strategy.cpp index 5a2a5da313..f3973ca9cc 100644 --- a/rclcpp/src/rclcpp/memory_strategy.cpp +++ b/rclcpp/src/rclcpp/memory_strategy.cpp @@ -127,7 +127,7 @@ MemoryStrategy::get_timer_by_handle( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr MemoryStrategy::get_node_by_group( - rclcpp::callback_group::CallbackGroup::SharedPtr group, + rclcpp::CallbackGroup::SharedPtr group, const WeakNodeList & weak_nodes) { if (!group) { @@ -148,7 +148,7 @@ MemoryStrategy::get_node_by_group( return nullptr; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_subscription( rclcpp::SubscriptionBase::SharedPtr subscription, const WeakNodeList & weak_nodes) @@ -175,7 +175,7 @@ MemoryStrategy::get_group_by_subscription( return nullptr; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_service( rclcpp::ServiceBase::SharedPtr service, const WeakNodeList & weak_nodes) @@ -202,7 +202,7 @@ MemoryStrategy::get_group_by_service( return nullptr; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_client( rclcpp::ClientBase::SharedPtr client, const WeakNodeList & weak_nodes) @@ -229,7 +229,7 @@ MemoryStrategy::get_group_by_client( return nullptr; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_timer( rclcpp::TimerBase::SharedPtr timer, const WeakNodeList & weak_nodes) @@ -256,7 +256,7 @@ MemoryStrategy::get_group_by_timer( return nullptr; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr MemoryStrategy::get_group_by_waitable( rclcpp::Waitable::SharedPtr waitable, const WeakNodeList & weak_nodes) diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index b73ec6bf2f..29a25eb645 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -210,15 +210,14 @@ Node::get_logger() const return node_logging_->get_logger(); } -rclcpp::callback_group::CallbackGroup::SharedPtr -Node::create_callback_group( - rclcpp::callback_group::CallbackGroupType group_type) +rclcpp::CallbackGroup::SharedPtr +Node::create_callback_group(rclcpp::CallbackGroupType group_type) { return node_base_->create_callback_group(group_type); } bool -Node::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group) +Node::group_in_node(rclcpp::CallbackGroup::SharedPtr group) { return node_base_->callback_group_in_node(group); } @@ -377,7 +376,7 @@ Node::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_ma return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle); } -const std::vector & +const std::vector & Node::get_callback_groups() const { return node_base_->get_callback_groups(); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp index 6a6f1e4fb1..0bdf2342e5 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp @@ -133,7 +133,7 @@ NodeBase::NodeBase( }); // Create the default callback group. - using rclcpp::callback_group::CallbackGroupType; + using rclcpp::CallbackGroupType; default_callback_group_ = create_callback_group(CallbackGroupType::MutuallyExclusive); // Indicate the notify_guard_condition is now valid. @@ -208,24 +208,24 @@ NodeBase::assert_liveliness() const return RCL_RET_OK == rcl_node_assert_liveliness(get_rcl_node_handle()); } -rclcpp::callback_group::CallbackGroup::SharedPtr -NodeBase::create_callback_group(rclcpp::callback_group::CallbackGroupType group_type) +rclcpp::CallbackGroup::SharedPtr +NodeBase::create_callback_group(rclcpp::CallbackGroupType group_type) { - using rclcpp::callback_group::CallbackGroup; - using rclcpp::callback_group::CallbackGroupType; + using rclcpp::CallbackGroup; + using rclcpp::CallbackGroupType; auto group = CallbackGroup::SharedPtr(new CallbackGroup(group_type)); callback_groups_.push_back(group); return group; } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr NodeBase::get_default_callback_group() { return default_callback_group_; } bool -NodeBase::callback_group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group) +NodeBase::callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) { bool group_belongs_to_this_node = false; for (auto & weak_group : this->callback_groups_) { @@ -237,7 +237,7 @@ NodeBase::callback_group_in_node(rclcpp::callback_group::CallbackGroup::SharedPt return group_belongs_to_this_node; } -const std::vector & +const std::vector & NodeBase::get_callback_groups() const { return callback_groups_; diff --git a/rclcpp/src/rclcpp/node_interfaces/node_services.cpp b/rclcpp/src/rclcpp/node_interfaces/node_services.cpp index 0e74f58907..ebb0de9bfb 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_services.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_services.cpp @@ -28,7 +28,7 @@ NodeServices::~NodeServices() void NodeServices::add_service( rclcpp::ServiceBase::SharedPtr service_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { if (group) { if (!node_base_->callback_group_in_node(group)) { @@ -55,7 +55,7 @@ NodeServices::add_service( void NodeServices::add_client( rclcpp::ClientBase::SharedPtr client_base_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { if (group) { if (!node_base_->callback_group_in_node(group)) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp index f9d5d720e8..d027a0650f 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp @@ -28,7 +28,7 @@ NodeTimers::~NodeTimers() void NodeTimers::add_timer( rclcpp::TimerBase::SharedPtr timer, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) + rclcpp::CallbackGroup::SharedPtr callback_group) { if (callback_group) { if (!node_base_->callback_group_in_node(callback_group)) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp b/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp index 360b4236c3..fced51c3f5 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_topics.cpp @@ -44,7 +44,7 @@ NodeTopics::create_publisher( void NodeTopics::add_publisher( rclcpp::PublisherBase::SharedPtr publisher, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) + rclcpp::CallbackGroup::SharedPtr callback_group) { // Assign to a group. if (callback_group) { @@ -83,7 +83,7 @@ NodeTopics::create_subscription( void NodeTopics::add_subscription( rclcpp::SubscriptionBase::SharedPtr subscription, - rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) + rclcpp::CallbackGroup::SharedPtr callback_group) { // Assign to a group. if (callback_group) { diff --git a/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp b/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp index ee9a2da2de..0fd083788a 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp @@ -28,7 +28,7 @@ NodeWaitables::~NodeWaitables() void NodeWaitables::add_waitable( rclcpp::Waitable::SharedPtr waitable_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { if (group) { if (!node_base_->callback_group_in_node(group)) { @@ -55,7 +55,7 @@ NodeWaitables::add_waitable( void NodeWaitables::remove_waitable( rclcpp::Waitable::SharedPtr waitable_ptr, - rclcpp::callback_group::CallbackGroup::SharedPtr group) noexcept + rclcpp::CallbackGroup::SharedPtr group) noexcept { if (group) { if (!node_base_->callback_group_in_node(group)) { diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 3146504005..03a59c6618 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -31,7 +31,7 @@ AsyncParametersClient::AsyncParametersClient( const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) : node_topics_interface_(node_topics_interface) { if (remote_node_name != "") { @@ -103,7 +103,7 @@ AsyncParametersClient::AsyncParametersClient( const rclcpp::Node::SharedPtr node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) : AsyncParametersClient( node->get_node_base_interface(), node->get_node_topics_interface(), @@ -118,7 +118,7 @@ AsyncParametersClient::AsyncParametersClient( rclcpp::Node * node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) : AsyncParametersClient( node->get_node_base_interface(), node->get_node_topics_interface(), @@ -349,7 +349,7 @@ SyncParametersClient::SyncParametersClient( {} SyncParametersClient::SyncParametersClient( - rclcpp::executor::Executor::SharedPtr executor, + rclcpp::Executor::SharedPtr executor, rclcpp::Node::SharedPtr node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile) @@ -375,7 +375,7 @@ SyncParametersClient::SyncParametersClient( {} SyncParametersClient::SyncParametersClient( - rclcpp::executor::Executor::SharedPtr executor, + rclcpp::Executor::SharedPtr executor, rclcpp::Node * node, const std::string & remote_node_name, const rmw_qos_profile_t & qos_profile) @@ -390,7 +390,7 @@ SyncParametersClient::SyncParametersClient( {} SyncParametersClient::SyncParametersClient( - rclcpp::executor::Executor::SharedPtr executor, + 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, @@ -417,7 +417,7 @@ SyncParametersClient::get_parameters(const std::vector & parameter_ if ( spin_node_until_future_complete( *executor_, node_base_interface_, - f) == rclcpp::executor::FutureReturnCode::SUCCESS) + f) == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } @@ -443,7 +443,7 @@ SyncParametersClient::get_parameter_types(const std::vector & param if ( spin_node_until_future_complete( *executor_, node_base_interface_, - f) == rclcpp::executor::FutureReturnCode::SUCCESS) + f) == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } @@ -460,7 +460,7 @@ SyncParametersClient::set_parameters( if ( spin_node_until_future_complete( *executor_, node_base_interface_, - f) == rclcpp::executor::FutureReturnCode::SUCCESS) + f) == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } @@ -477,7 +477,7 @@ SyncParametersClient::set_parameters_atomically( if ( spin_node_until_future_complete( *executor_, node_base_interface_, - f) == rclcpp::executor::FutureReturnCode::SUCCESS) + f) == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } @@ -496,7 +496,7 @@ SyncParametersClient::list_parameters( if ( spin_node_until_future_complete( *executor_, node_base_interface_, - f) == rclcpp::executor::FutureReturnCode::SUCCESS) + f) == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } diff --git a/rclcpp/src/rclcpp/timer.cpp b/rclcpp/src/rclcpp/timer.cpp index 6dc8759973..9ece178c28 100644 --- a/rclcpp/src/rclcpp/timer.cpp +++ b/rclcpp/src/rclcpp/timer.cpp @@ -33,7 +33,7 @@ TimerBase::TimerBase( : clock_(clock), timer_handle_(nullptr) { if (nullptr == context) { - context = rclcpp::contexts::default_context::get_global_default_context(); + context = rclcpp::contexts::get_global_default_context(); } auto rcl_context = context->get_rcl_context(); diff --git a/rclcpp/src/rclcpp/utilities.cpp b/rclcpp/src/rclcpp/utilities.cpp index 4cbfd27aaa..0c4f0cd705 100644 --- a/rclcpp/src/rclcpp/utilities.cpp +++ b/rclcpp/src/rclcpp/utilities.cpp @@ -30,7 +30,7 @@ namespace rclcpp void init(int argc, char const * const argv[], const InitOptions & init_options) { - using contexts::default_context::get_global_default_context; + using rclcpp::contexts::get_global_default_context; get_global_default_context()->init(argc, argv, init_options); // Install the signal handlers. install_signal_handlers(); @@ -125,7 +125,7 @@ remove_ros_arguments(int argc, char const * const argv[]) bool ok(Context::SharedPtr context) { - using contexts::default_context::get_global_default_context; + using rclcpp::contexts::get_global_default_context; if (nullptr == context) { context = get_global_default_context(); } @@ -141,7 +141,7 @@ is_initialized(Context::SharedPtr context) bool shutdown(Context::SharedPtr context, const std::string & reason) { - using contexts::default_context::get_global_default_context; + using rclcpp::contexts::get_global_default_context; auto default_context = get_global_default_context(); if (nullptr == context) { context = default_context; @@ -156,7 +156,7 @@ shutdown(Context::SharedPtr context, const std::string & reason) void on_shutdown(std::function callback, Context::SharedPtr context) { - using contexts::default_context::get_global_default_context; + using rclcpp::contexts::get_global_default_context; if (nullptr == context) { context = get_global_default_context(); } @@ -166,7 +166,7 @@ on_shutdown(std::function callback, Context::SharedPtr context) bool sleep_for(const std::chrono::nanoseconds & nanoseconds, Context::SharedPtr context) { - using contexts::default_context::get_global_default_context; + using rclcpp::contexts::get_global_default_context; if (nullptr == context) { context = get_global_default_context(); } diff --git a/rclcpp/test/executors/test_multi_threaded_executor.cpp b/rclcpp/test/executors/test_multi_threaded_executor.cpp index 391c995859..e4d648190f 100644 --- a/rclcpp/test/executors/test_multi_threaded_executor.cpp +++ b/rclcpp/test/executors/test_multi_threaded_executor.cpp @@ -51,14 +51,14 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) { bool yield_before_execute = true; rclcpp::executors::MultiThreadedExecutor executor( - rclcpp::executor::create_default_executor_arguments(), 2u, yield_before_execute); + rclcpp::ExecutorOptions(), 2u, yield_before_execute); ASSERT_GT(executor.get_number_of_threads(), 1u); std::shared_ptr node = std::make_shared("test_multi_threaded_executor_timer_over_take"); - auto cbg = node->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant); + auto cbg = node->create_callback_group(rclcpp::CallbackGroupType::Reentrant); rclcpp::Clock system_clock(RCL_STEADY_TIME); std::mutex last_mutex; diff --git a/rclcpp/test/test_interface_traits.cpp b/rclcpp/test/test_interface_traits.cpp index 599517c328..071ac22ce7 100644 --- a/rclcpp/test/test_interface_traits.cpp +++ b/rclcpp/test/test_interface_traits.cpp @@ -31,7 +31,7 @@ class MyNode return std::make_shared( "my_node_name", "my_node_namespace", - rclcpp::contexts::default_context::get_global_default_context(), + rclcpp::contexts::get_global_default_context(), *options.get_rcl_node_options(), options.use_intra_process_comms(), options.enable_topic_statistics()); diff --git a/rclcpp/test/test_utilities.cpp b/rclcpp/test/test_utilities.cpp index 8dd8d58a0c..d0e05f9bbb 100644 --- a/rclcpp/test/test_utilities.cpp +++ b/rclcpp/test/test_utilities.cpp @@ -52,8 +52,8 @@ TEST(TestUtilities, init_with_args) { } TEST(TestUtilities, multi_init) { - auto context1 = std::make_shared(); - auto context2 = std::make_shared(); + auto context1 = std::make_shared(); + auto context2 = std::make_shared(); EXPECT_FALSE(rclcpp::ok(context1)); EXPECT_FALSE(rclcpp::ok(context2)); diff --git a/rclcpp_action/include/rclcpp_action/create_client.hpp b/rclcpp_action/include/rclcpp_action/create_client.hpp index 6a356ce1aa..2acd4d7aee 100644 --- a/rclcpp_action/include/rclcpp_action/create_client.hpp +++ b/rclcpp_action/include/rclcpp_action/create_client.hpp @@ -46,11 +46,11 @@ create_client( rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string & name, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr) + rclcpp::CallbackGroup::SharedPtr group = nullptr) { std::weak_ptr weak_node = node_waitables_interface; - std::weak_ptr weak_group = group; + std::weak_ptr weak_group = group; bool group_is_null = (nullptr == group.get()); auto deleter = [weak_node, weak_group, group_is_null](Client * ptr) @@ -102,9 +102,9 @@ typename Client::SharedPtr create_client( NodeT node, const std::string & name, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr) + rclcpp::CallbackGroup::SharedPtr group = nullptr) { - return create_client( + return rclcpp_action::create_client( node->get_node_base_interface(), node->get_node_graph_interface(), node->get_node_logging_interface(), diff --git a/rclcpp_action/include/rclcpp_action/create_server.hpp b/rclcpp_action/include/rclcpp_action/create_server.hpp index afd24cd285..2886ee9c97 100644 --- a/rclcpp_action/include/rclcpp_action/create_server.hpp +++ b/rclcpp_action/include/rclcpp_action/create_server.hpp @@ -65,11 +65,11 @@ create_server( typename Server::CancelCallback handle_cancel, typename Server::AcceptedCallback handle_accepted, const rcl_action_server_options_t & options = rcl_action_server_get_default_options(), - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr) + rclcpp::CallbackGroup::SharedPtr group = nullptr) { std::weak_ptr weak_node = node_waitables_interface; - std::weak_ptr weak_group = group; + std::weak_ptr weak_group = group; bool group_is_null = (nullptr == group.get()); auto deleter = [weak_node, weak_group, group_is_null](Server * ptr) @@ -137,7 +137,7 @@ create_server( typename Server::CancelCallback handle_cancel, typename Server::AcceptedCallback handle_accepted, const rcl_action_server_options_t & options = rcl_action_server_get_default_options(), - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr) + rclcpp::CallbackGroup::SharedPtr group = nullptr) { return create_server( node->get_node_base_interface(), diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 35e2c4e032..8dd20828cd 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -49,7 +49,7 @@ class TestServer : public ::testing::Test request->goal_id.uuid = uuid; auto future = client->async_send_request(request); if ( - rclcpp::executor::FutureReturnCode::SUCCESS != + rclcpp::FutureReturnCode::SUCCESS != rclcpp::spin_until_future_complete(node, future)) { throw std::runtime_error("send goal future didn't complete succesfully"); @@ -69,7 +69,7 @@ class TestServer : public ::testing::Test request->goal_info.goal_id.uuid = uuid; auto future = cancel_client->async_send_request(request); if ( - rclcpp::executor::FutureReturnCode::SUCCESS != + rclcpp::FutureReturnCode::SUCCESS != rclcpp::spin_until_future_complete(node, future)) { throw std::runtime_error("cancel goal future didn't complete succesfully"); @@ -132,7 +132,7 @@ TEST_F(TestServer, handle_goal_called) auto future = client->async_send_request(request); ASSERT_EQ( - rclcpp::executor::FutureReturnCode::SUCCESS, + rclcpp::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, future)); ASSERT_EQ(uuid, received_uuid); @@ -744,7 +744,7 @@ TEST_F(TestServer, get_result) // Wait for the result request to be received ASSERT_EQ( - rclcpp::executor::FutureReturnCode::SUCCESS, + rclcpp::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, future)); auto response = future.get(); diff --git a/rclcpp_components/include/rclcpp_components/component_manager.hpp b/rclcpp_components/include/rclcpp_components/component_manager.hpp index 0003b07e5a..20d2d7b890 100644 --- a/rclcpp_components/include/rclcpp_components/component_manager.hpp +++ b/rclcpp_components/include/rclcpp_components/component_manager.hpp @@ -62,7 +62,7 @@ class ComponentManager : public rclcpp::Node RCLCPP_COMPONENTS_PUBLIC ComponentManager( - std::weak_ptr executor, + std::weak_ptr executor, std::string node_name = "ComponentManager", const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions()); @@ -103,7 +103,7 @@ class ComponentManager : public rclcpp::Node std::shared_ptr response); private: - std::weak_ptr executor_; + std::weak_ptr executor_; uint64_t unique_id_ {1}; std::map> loaders_; diff --git a/rclcpp_components/src/component_manager.cpp b/rclcpp_components/src/component_manager.cpp index 720d713031..a80fada378 100644 --- a/rclcpp_components/src/component_manager.cpp +++ b/rclcpp_components/src/component_manager.cpp @@ -31,7 +31,7 @@ namespace rclcpp_components { ComponentManager::ComponentManager( - std::weak_ptr executor, + std::weak_ptr executor, std::string node_name, const rclcpp::NodeOptions & node_options) : Node(std::move(node_name), node_options), diff --git a/rclcpp_components/test/test_component_manager_api.cpp b/rclcpp_components/test/test_component_manager_api.cpp index 1d39b04738..a13bf22ec4 100644 --- a/rclcpp_components/test/test_component_manager_api.cpp +++ b/rclcpp_components/test/test_component_manager_api.cpp @@ -59,7 +59,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, true); EXPECT_EQ(result.get()->error_message, ""); EXPECT_EQ(result.get()->full_node_name, "/test_component_foo"); @@ -73,7 +73,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, true); EXPECT_EQ(result.get()->error_message, ""); EXPECT_EQ(result.get()->full_node_name, "/test_component_bar"); @@ -89,7 +89,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, true); EXPECT_EQ(result.get()->error_message, ""); EXPECT_EQ(result.get()->full_node_name, "/test_component_baz"); @@ -106,7 +106,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, true); EXPECT_EQ(result.get()->error_message, ""); EXPECT_EQ(result.get()->full_node_name, "/ns/test_component_bing"); @@ -121,7 +121,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, false); EXPECT_EQ(result.get()->error_message, "Failed to find class with the requested plugin name."); EXPECT_EQ(result.get()->full_node_name, ""); @@ -136,7 +136,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, false); EXPECT_EQ(result.get()->error_message, "Could not find requested resource in ament index"); EXPECT_EQ(result.get()->full_node_name, ""); @@ -166,7 +166,7 @@ TEST_F(TestComponentManager, components_api) auto request = std::make_shared(); auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto node_names = result.get()->full_node_names; auto unique_ids = result.get()->unique_ids; @@ -197,7 +197,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, true); EXPECT_EQ(result.get()->error_message, ""); } @@ -208,7 +208,7 @@ TEST_F(TestComponentManager, components_api) auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result.get()->success, false); EXPECT_EQ(result.get()->error_message, "No node found with unique_id: 1"); } @@ -226,7 +226,7 @@ TEST_F(TestComponentManager, components_api) auto request = std::make_shared(); auto result = client->async_send_request(request); auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result. - EXPECT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto node_names = result.get()->full_node_names; auto unique_ids = result.get()->unique_ids; diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 6b6c213fd5..73d728ba41 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -146,12 +146,12 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, /// Create and return a callback group. RCLCPP_LIFECYCLE_PUBLIC - rclcpp::callback_group::CallbackGroup::SharedPtr - create_callback_group(rclcpp::callback_group::CallbackGroupType group_type); + rclcpp::CallbackGroup::SharedPtr + create_callback_group(rclcpp::CallbackGroupType group_type); /// Return the list of callback groups in the node. RCLCPP_LIFECYCLE_PUBLIC - const std::vector & + const std::vector & get_callback_groups() const; /// Create and return a Publisher. @@ -214,7 +214,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, create_wall_timer( std::chrono::duration period, CallbackT callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); /* Create and return a Client. */ template @@ -222,7 +222,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); /* Create and return a Service. */ template @@ -231,7 +231,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr); /// Declare and initialize a parameter, return the effective value. /** @@ -659,7 +659,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, RCLCPP_LIFECYCLE_PUBLIC bool - group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group); + group_in_node(rclcpp::CallbackGroup::SharedPtr group); rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_; rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_; diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index c09031926a..be79e7944a 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -84,7 +84,7 @@ typename rclcpp::WallTimer::SharedPtr LifecycleNode::create_wall_timer( std::chrono::duration period, CallbackT callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { auto timer = rclcpp::WallTimer::make_shared( std::chrono::duration_cast(period), @@ -98,7 +98,7 @@ typename rclcpp::Client::SharedPtr LifecycleNode::create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { rcl_client_options_t options = rcl_client_get_default_options(); options.qos = qos_profile; @@ -123,7 +123,7 @@ LifecycleNode::create_service( const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group) + rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_service( node_base_, node_services_, diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index 60debba6f7..7b36f1f753 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -146,9 +146,9 @@ LifecycleNode::get_logger() const return node_logging_->get_logger(); } -rclcpp::callback_group::CallbackGroup::SharedPtr +rclcpp::CallbackGroup::SharedPtr LifecycleNode::create_callback_group( - rclcpp::callback_group::CallbackGroupType group_type) + rclcpp::CallbackGroupType group_type) { return node_base_->create_callback_group(group_type); } @@ -181,7 +181,7 @@ LifecycleNode::set_parameter(const rclcpp::Parameter & parameter) } bool -LifecycleNode::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group) +LifecycleNode::group_in_node(rclcpp::CallbackGroup::SharedPtr group) { return node_base_->callback_group_in_node(group); } @@ -303,7 +303,7 @@ LifecycleNode::get_subscriptions_info_by_topic(const std::string & topic_name, b return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle); } -const std::vector & +const std::vector & LifecycleNode::get_callback_groups() const { return node_base_->get_callback_groups();