diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index 149d49fa20..1b86c01119 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -23,6 +23,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() include_directories(include) +include(cmake/configure_rclcpp.cmake) set(${PROJECT_NAME}_SRCS src/rclcpp/any_executable.cpp @@ -109,6 +110,7 @@ ament_target_dependencies(${PROJECT_NAME} "rosidl_typesupport_cpp" "rosidl_generator_cpp") +configure_rclcpp(${PROJECT_NAME}) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. target_compile_definitions(${PROJECT_NAME} diff --git a/rclcpp/cmake/configure_rclcpp.cmake b/rclcpp/cmake/configure_rclcpp.cmake new file mode 100644 index 0000000000..f981e3422e --- /dev/null +++ b/rclcpp/cmake/configure_rclcpp.cmake @@ -0,0 +1,66 @@ +# Copyright 2019 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. +# +# Configures ros client library with custom settings. +# The custom settings are all related to library symbol visibility, see: +# https://gcc.gnu.org/wiki/Visibility +# http://www.ibm.com/developerworks/aix/library/au-aix-symbol-visibility/ +# +# Below code is heavily referenced from a similar functionality in rmw: +# https://github.com/ros2/rmw/blob/master/rmw/cmake/configure_rmw_library.cmake +# +# :param library_target: the library target +# :type library_target: string +# :param LANGUAGE: Optional flag for the language of the library. +# Allowed values are "C" and "CXX". The default is "CXX". +# :type LANGUAGE: string +# +# @public +# +macro(configure_rclcpp library_target) + cmake_parse_arguments(_ARG "" "LANGUAGE" "" ${ARGN}) + if(_ARG_UNPARSED_ARGUMENTS) + message(FATAL_ERROR "configure_rclcpp() called with unused arguments: ${_ARG_UNPARSED_ARGUMENTS}") + endif() + + if(NOT _ARG_LANGUAGE) + set(_ARG_LANGUAGE "CXX") + endif() + + if(_ARG_LANGUAGE STREQUAL "C") + # Set the visibility to hidden by default if possible + if(CMAKE_C_COMPILER_ID STREQUAL "GNU" OR CMAKE_C_COMPILER_ID MATCHES "Clang") + # Set the visibility of symbols to hidden by default for gcc and clang + # (this is already the default on Windows) + set_target_properties(${library_target} + PROPERTIES + COMPILE_FLAGS "-fvisibility=hidden" + ) + endif() + + elseif(_ARG_LANGUAGE STREQUAL "CXX") + # Set the visibility to hidden by default if possible + if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + # Set the visibility of symbols to hidden by default for gcc and clang + # (this is already the default on Windows) + set_target_properties(${library_target} + PROPERTIES + COMPILE_FLAGS "-fvisibility=hidden -fvisibility-inlines-hidden" + ) + endif() + + else() + message(FATAL_ERROR "configure_rclcpp() called with unsupported LANGUAGE: '${_ARG_LANGUAGE}'") + endif() +endmacro() diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 1f22b55c6d..bae36e4b22 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -49,32 +49,26 @@ namespace node_interfaces class NodeBaseInterface; } // namespace node_interfaces -class ClientBase +class RCLCPP_PUBLIC ClientBase { public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase) - RCLCPP_PUBLIC ClientBase( rclcpp::node_interfaces::NodeBaseInterface * node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph); - RCLCPP_PUBLIC virtual ~ClientBase(); - RCLCPP_PUBLIC const char * get_service_name() const; - RCLCPP_PUBLIC std::shared_ptr get_client_handle(); - RCLCPP_PUBLIC std::shared_ptr get_client_handle() const; - RCLCPP_PUBLIC bool service_is_ready() const; @@ -96,15 +90,12 @@ class ClientBase protected: RCLCPP_DISABLE_COPY(ClientBase) - RCLCPP_PUBLIC bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout); - RCLCPP_PUBLIC rcl_node_t * get_rcl_node_handle(); - RCLCPP_PUBLIC const rcl_node_t * get_rcl_node_handle() const; diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 2de4bdaea4..30125f8171 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -92,18 +92,16 @@ static inline ExecutorArgs create_default_executor_arguments() * model. * See SingleThreadedExecutor and MultiThreadedExecutor for examples of execution paradigms. */ -class Executor +class RCLCPP_PUBLIC Executor { public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Executor) /// Default constructor. // \param[in] ms The memory strategy to be used with this executor. - RCLCPP_PUBLIC explicit Executor(const ExecutorArgs & args = ExecutorArgs()); /// Default destructor. - RCLCPP_PUBLIC virtual ~Executor(); /// Do work periodically as it becomes available to us. Blocking call, may block indefinitely. @@ -119,12 +117,10 @@ class Executor * the executor is blocked at the rmw layer while waiting for work and it is notified that a new * node was added, it will wake up. */ - RCLCPP_PUBLIC virtual void add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); /// Convenience function which takes Node and forwards NodeBaseInterface. - RCLCPP_PUBLIC virtual void add_node(std::shared_ptr node_ptr, bool notify = true); @@ -135,12 +131,10 @@ class Executor * This is useful if the last node was removed from the executor while the executor was blocked * waiting for work in another thread, because otherwise the executor would never be notified. */ - RCLCPP_PUBLIC virtual void remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); /// Convenience function which takes Node and forwards NodeBaseInterface. - RCLCPP_PUBLIC virtual void remove_node(std::shared_ptr node_ptr, bool notify = true); @@ -180,12 +174,10 @@ class Executor /** * \param[in] node Shared pointer to the node to add. */ - RCLCPP_PUBLIC void spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node); /// Convenience function which takes Node and forwards NodeBaseInterface. - RCLCPP_PUBLIC void spin_node_some(std::shared_ptr node); @@ -200,11 +192,9 @@ class Executor * Note that spin_some() may take longer than this time as it only returns once max_duration has * been exceeded. */ - RCLCPP_PUBLIC virtual void spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0)); - RCLCPP_PUBLIC virtual void spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); @@ -269,7 +259,6 @@ class Executor /// Cancel any running spin* function, causing it to return. /* This function can be called asynchonously from any thread. */ - RCLCPP_PUBLIC void cancel(); @@ -279,12 +268,10 @@ class Executor * unintended consequences. * \param[in] memory_strategy Shared pointer to the memory strategy to set. */ - RCLCPP_PUBLIC void set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy); protected: - RCLCPP_PUBLIC void spin_node_once_nanoseconds( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, @@ -294,53 +281,41 @@ class Executor /** \param[in] any_exec Union structure that can hold any executable type (timer, subscription, * service, client). */ - RCLCPP_PUBLIC void execute_any_executable(AnyExecutable & any_exec); - RCLCPP_PUBLIC static void execute_subscription( rclcpp::SubscriptionBase::SharedPtr subscription); - RCLCPP_PUBLIC static void execute_intra_process_subscription( rclcpp::SubscriptionBase::SharedPtr subscription); - RCLCPP_PUBLIC static void execute_timer(rclcpp::TimerBase::SharedPtr timer); - RCLCPP_PUBLIC static void execute_service(rclcpp::ServiceBase::SharedPtr service); - RCLCPP_PUBLIC static void execute_client(rclcpp::ClientBase::SharedPtr client); - RCLCPP_PUBLIC void wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group); - RCLCPP_PUBLIC rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_timer(rclcpp::TimerBase::SharedPtr timer); - RCLCPP_PUBLIC void get_next_timer(AnyExecutable & any_exec); - RCLCPP_PUBLIC bool get_next_ready_executable(AnyExecutable & any_executable); - RCLCPP_PUBLIC bool get_next_executable( AnyExecutable & any_executable, diff --git a/rclcpp/include/rclcpp/intra_process_manager.hpp b/rclcpp/include/rclcpp/intra_process_manager.hpp index 6c044a4da6..aa47b36d93 100644 --- a/rclcpp/include/rclcpp/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager.hpp @@ -119,7 +119,7 @@ namespace intra_process_manager * * This class is neither CopyConstructable nor CopyAssignable. */ -class IntraProcessManager +class RCLCPP_PUBLIC IntraProcessManager { private: RCLCPP_DISABLE_COPY(IntraProcessManager) @@ -127,11 +127,9 @@ class IntraProcessManager public: RCLCPP_SMART_PTR_DEFINITIONS(IntraProcessManager) - RCLCPP_PUBLIC explicit IntraProcessManager( IntraProcessManagerImplBase::SharedPtr state = create_default_impl()); - RCLCPP_PUBLIC virtual ~IntraProcessManager(); /// Register a subscription with the manager, returns subscriptions unique id. @@ -147,7 +145,6 @@ class IntraProcessManager * \param subscription the Subscription to register. * \return an unsigned 64-bit integer which is the subscription's unique id. */ - RCLCPP_PUBLIC uint64_t add_subscription(SubscriptionBase::SharedPtr subscription); @@ -157,7 +154,6 @@ class IntraProcessManager * * \param intra_process_subscription_id id of the subscription to remove. */ - RCLCPP_PUBLIC void remove_subscription(uint64_t intra_process_subscription_id); @@ -206,7 +202,6 @@ class IntraProcessManager * * \param intra_process_publisher_id id of the publisher to remove. */ - RCLCPP_PUBLIC void remove_publisher(uint64_t intra_process_publisher_id); @@ -342,17 +337,14 @@ class IntraProcessManager } /// Return true if the given rmw_gid_t matches any stored Publishers. - RCLCPP_PUBLIC bool matches_any_publishers(const rmw_gid_t * id) const; /// Return the number of intraprocess subscriptions to a topic, given the publisher id. - RCLCPP_PUBLIC size_t get_subscription_count(uint64_t intra_process_publisher_id) const; private: - RCLCPP_PUBLIC static uint64_t get_next_unique_id(); diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 1f1a24b108..ef1db8016c 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -65,7 +65,7 @@ namespace rclcpp { /// Node is the single point of entry for creating publishers and subscribers. -class Node : public std::enable_shared_from_this +class RCLCPP_PUBLIC Node : public std::enable_shared_from_this { public: RCLCPP_SMART_PTR_DEFINITIONS(Node) @@ -75,7 +75,6 @@ class Node : public std::enable_shared_from_this * \param[in] node_name Name of the node. * \param[in] options Additional options to control creation of the node. */ - RCLCPP_PUBLIC explicit Node( const std::string & node_name, const NodeOptions & options = NodeOptions()); @@ -86,18 +85,15 @@ class Node : public std::enable_shared_from_this * \param[in] namespace_ Namespace of the node. * \param[in] options Additional options to control creation of the node. */ - RCLCPP_PUBLIC explicit Node( const std::string & node_name, const std::string & namespace_, const NodeOptions & options = NodeOptions()); - RCLCPP_PUBLIC virtual ~Node(); /// Get the name of the node. /** \return The name of the node. */ - RCLCPP_PUBLIC const char * get_name() const; @@ -111,23 +107,19 @@ class Node : public std::enable_shared_from_this * \sa get_effective_namespace() * \return The namespace of the node. */ - RCLCPP_PUBLIC const char * get_namespace() const; /// Get the logger of the node. /** \return The logger of the node. */ - RCLCPP_PUBLIC rclcpp::Logger get_logger() const; /// Create and return a callback group. - RCLCPP_PUBLIC rclcpp::callback_group::CallbackGroup::SharedPtr create_callback_group(rclcpp::callback_group::CallbackGroupType group_type); /// Return the list of callback groups in the node. - RCLCPP_PUBLIC const std::vector & get_callback_groups() const; @@ -258,11 +250,9 @@ class Node : public std::enable_shared_from_this const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); - RCLCPP_PUBLIC std::vector set_parameters(const std::vector & parameters); - RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector & parameters); @@ -286,15 +276,12 @@ class Node : public std::enable_shared_from_this const std::string & name, const std::map & values); - RCLCPP_PUBLIC std::vector get_parameters(const std::vector & names) const; - RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string & name) const; - RCLCPP_PUBLIC bool get_parameter( const std::string & name, @@ -366,15 +353,12 @@ class Node : public std::enable_shared_from_this ParameterT & value, const ParameterT & alternative_value); - RCLCPP_PUBLIC std::vector describe_parameters(const std::vector & names) const; - RCLCPP_PUBLIC std::vector get_parameter_types(const std::vector & names) const; - RCLCPP_PUBLIC rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const; @@ -388,23 +372,18 @@ class Node : public std::enable_shared_from_this void register_param_change_callback(CallbackT && callback); - RCLCPP_PUBLIC std::vector get_node_names() const; - RCLCPP_PUBLIC std::map> get_topic_names_and_types() const; - RCLCPP_PUBLIC std::map> get_service_names_and_types() const; - RCLCPP_PUBLIC size_t count_publishers(const std::string & topic_name) const; - RCLCPP_PUBLIC size_t count_subscribers(const std::string & topic_name) const; @@ -413,7 +392,6 @@ class Node : public std::enable_shared_from_this * The Event object is scoped and therefore to return the loan just let it go * out of scope. */ - RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event(); @@ -425,67 +403,54 @@ class Node : public std::enable_shared_from_this * \throws EventNotRegisteredError if the given event was not acquired with * get_graph_event(). */ - RCLCPP_PUBLIC void wait_for_graph_change( rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout); - RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock(); - RCLCPP_PUBLIC Time now(); /// Return the Node's internal NodeBaseInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface(); /// Return the Node's internal NodeClockInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface(); /// Return the Node's internal NodeGraphInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface(); /// Return the Node's internal NodeLoggingInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface(); /// Return the Node's internal NodeTimersInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface(); /// Return the Node's internal NodeTopicsInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface(); /// Return the Node's internal NodeServicesInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface(); /// Return the Node's internal NodeWaitablesInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface(); /// Return the Node's internal NodeParametersInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface(); /// Return the Node's internal NodeParametersInterface implementation. - RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface(); @@ -515,7 +480,6 @@ class Node : public std::enable_shared_from_this * \sa get_effective_namespace() * \return the sub-namespace string, not including the node's original namespace */ - RCLCPP_PUBLIC const std::string & get_sub_namespace() const; @@ -541,7 +505,6 @@ class Node : public std::enable_shared_from_this * \sa get_sub_namespace() * \return the sub-namespace string, not including the node's original namespace */ - RCLCPP_PUBLIC const std::string & get_effective_namespace() const; @@ -583,12 +546,10 @@ class Node : public std::enable_shared_from_this * \throws NameValidationError if the sub-namespace is absolute, i.e. starts * with a leading '/'. */ - RCLCPP_PUBLIC Node::SharedPtr create_sub_node(const std::string & sub_namespace); /// Return the NodeOptions used when creating this node. - RCLCPP_PUBLIC const NodeOptions & get_node_options() const; @@ -600,7 +561,6 @@ class Node : public std::enable_shared_from_this * \param[in] other The node from which a new sub-node is created. * \param[in] sub_namespace The sub-namespace of the sub-node. */ - RCLCPP_PUBLIC Node( const Node & other, const std::string & sub_namespace); @@ -608,7 +568,6 @@ class Node : public std::enable_shared_from_this private: RCLCPP_DISABLE_COPY(Node) - RCLCPP_PUBLIC bool group_in_node(callback_group::CallbackGroup::SharedPtr group); diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 4500fedab5..5565b30356 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -54,7 +54,7 @@ namespace intra_process_manager class IntraProcessManager; } -class PublisherBase +class RCLCPP_PUBLIC PublisherBase { friend ::rclcpp::node_interfaces::NodeTopicsInterface; @@ -70,61 +70,51 @@ class PublisherBase * \param[in] type_support The type support structure for the type to be published. * \param[in] publisher_options QoS settings for this publisher. */ - RCLCPP_PUBLIC PublisherBase( rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic, const rosidl_message_type_support_t & type_support, const rcl_publisher_options_t & publisher_options); - RCLCPP_PUBLIC virtual ~PublisherBase(); /// Get the topic that this publisher publishes on. /** \return The topic name. */ - RCLCPP_PUBLIC const char * get_topic_name() const; /// Get the queue size for this publisher. /** \return The queue size. */ - RCLCPP_PUBLIC size_t get_queue_size() const; /// Get the global identifier for this publisher (used in rmw and by DDS). /** \return The gid. */ - RCLCPP_PUBLIC const rmw_gid_t & get_gid() const; /// Get the global identifier for this publisher used by intra-process communication. /** \return The intra-process gid. */ - RCLCPP_PUBLIC const rmw_gid_t & get_intra_process_gid() const; /// Get the rcl publisher handle. /** \return The rcl publisher handle. */ - RCLCPP_PUBLIC rcl_publisher_t * get_publisher_handle(); /// Get the rcl publisher handle. /** \return The rcl publisher handle. */ - RCLCPP_PUBLIC const rcl_publisher_t * get_publisher_handle() const; /// Get subscription count /** \return The number of subscriptions. */ - RCLCPP_PUBLIC size_t get_subscription_count() const; /// Get intraprocess subscription count /** \return The number of intraprocess subscriptions. */ - RCLCPP_PUBLIC size_t get_intra_process_subscription_count() const; @@ -134,7 +124,6 @@ class PublisherBase * \param[in] gid Reference to a gid. * \return True if the publisher's gid matches the input. */ - RCLCPP_PUBLIC bool operator==(const rmw_gid_t & gid) const; @@ -144,7 +133,6 @@ class PublisherBase * \param[in] gid A pointer to a gid. * \return True if this publisher's gid matches the input. */ - RCLCPP_PUBLIC bool operator==(const rmw_gid_t * gid) const; @@ -153,7 +141,6 @@ class PublisherBase std::shared_ptr; /// Implementation utility function used to setup intra process publishing after creation. - RCLCPP_PUBLIC void setup_intra_process( uint64_t intra_process_publisher_id, diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 9dc8d027b0..e75839ce69 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -37,27 +37,22 @@ namespace rclcpp { -class ServiceBase +class RCLCPP_PUBLIC ServiceBase { public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase) - RCLCPP_PUBLIC explicit ServiceBase( std::shared_ptr node_handle); - RCLCPP_PUBLIC virtual ~ServiceBase(); - RCLCPP_PUBLIC const char * get_service_name(); - RCLCPP_PUBLIC std::shared_ptr get_service_handle(); - RCLCPP_PUBLIC std::shared_ptr get_service_handle() const; @@ -70,11 +65,9 @@ class ServiceBase protected: RCLCPP_DISABLE_COPY(ServiceBase) - RCLCPP_PUBLIC rcl_node_t * get_rcl_node_handle(); - RCLCPP_PUBLIC const rcl_node_t * get_rcl_node_handle() const; diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 2a2a3e4eef..b230d730f9 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -57,7 +57,7 @@ class IntraProcessManager; /// Virtual base class for subscriptions. This pattern allows us to iterate over different template /// specializations of Subscription, among other things. -class SubscriptionBase +class RCLCPP_PUBLIC SubscriptionBase { public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(SubscriptionBase) @@ -70,7 +70,6 @@ class SubscriptionBase * \param[in] subscription_options options for the subscription. * \param[in] is_serialized is true if the message will be delivered still serialized */ - RCLCPP_PUBLIC SubscriptionBase( std::shared_ptr node_handle, const rosidl_message_type_support_t & type_support_handle, @@ -79,23 +78,18 @@ class SubscriptionBase bool is_serialized = false); /// Default destructor. - RCLCPP_PUBLIC virtual ~SubscriptionBase(); /// Get the topic that this subscription is subscribed on. - RCLCPP_PUBLIC const char * get_topic_name() const; - RCLCPP_PUBLIC std::shared_ptr get_subscription_handle(); - RCLCPP_PUBLIC const std::shared_ptr get_subscription_handle() const; - RCLCPP_PUBLIC virtual const std::shared_ptr get_intra_process_subscription_handle() const; @@ -140,7 +134,6 @@ class SubscriptionBase /// Get matching publisher count /** \return The number of publishers on this topic. */ - RCLCPP_PUBLIC size_t get_publisher_count() const; diff --git a/rclcpp/include/rclcpp/waitable.hpp b/rclcpp/include/rclcpp/waitable.hpp index 4f48bbc238..538e61ef07 100644 --- a/rclcpp/include/rclcpp/waitable.hpp +++ b/rclcpp/include/rclcpp/waitable.hpp @@ -23,7 +23,7 @@ namespace rclcpp { -class Waitable +class RCLCPP_PUBLIC Waitable { public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Waitable) @@ -34,7 +34,6 @@ class Waitable * This should be overridden if the Waitable contains one or more subscriptions. * \return The number of subscriptions associated with the Waitable. */ - RCLCPP_PUBLIC virtual size_t get_number_of_ready_subscriptions(); @@ -45,7 +44,6 @@ class Waitable * This should be overridden if the Waitable contains one or more timers. * \return The number of timers associated with the Waitable. */ - RCLCPP_PUBLIC virtual size_t get_number_of_ready_timers(); @@ -56,7 +54,6 @@ class Waitable * This should be overridden if the Waitable contains one or more clients. * \return The number of clients associated with the Waitable. */ - RCLCPP_PUBLIC virtual size_t get_number_of_ready_clients(); @@ -67,7 +64,6 @@ class Waitable * This should be overridden if the Waitable contains one or more services. * \return The number of services associated with the Waitable. */ - RCLCPP_PUBLIC virtual size_t get_number_of_ready_services(); @@ -78,7 +74,6 @@ class Waitable * This should be overridden if the Waitable contains one or more guard_conditions. * \return The number of guard_conditions associated with the Waitable. */ - RCLCPP_PUBLIC virtual size_t get_number_of_ready_guard_conditions(); @@ -89,7 +84,6 @@ class Waitable * \param[in] wait_set A handle to the wait set to add the Waitable to. * \return `true` if the Waitable is added successfully, `false` otherwise. */ - RCLCPP_PUBLIC virtual bool add_to_wait_set(rcl_wait_set_t * wait_set) = 0; @@ -104,7 +98,6 @@ class Waitable * and that has been waited on. * \return `true` if the Waitable is ready, `false` otherwise. */ - RCLCPP_PUBLIC virtual bool is_ready(rcl_wait_set_t *) = 0; @@ -130,7 +123,6 @@ class Waitable * waitable.execute(); * ``` */ - RCLCPP_PUBLIC virtual void execute() = 0; diff --git a/rclcpp/rclcpp-extras.cmake b/rclcpp/rclcpp-extras.cmake index 7d3a1429fa..9bc22904a4 100644 --- a/rclcpp/rclcpp-extras.cmake +++ b/rclcpp/rclcpp-extras.cmake @@ -25,5 +25,6 @@ macro(_rclcpp_register_package_hook) endif() endmacro() +include("${rclcpp_DIR}/configure_rclcpp.cmake") include("${rclcpp_DIR}/rclcpp_create_node_main.cmake") include("${rclcpp_DIR}/rclcpp_register_node_plugins.cmake") diff --git a/rclcpp_action/CMakeLists.txt b/rclcpp_action/CMakeLists.txt index 29f85680c3..f3f6a972d8 100644 --- a/rclcpp_action/CMakeLists.txt +++ b/rclcpp_action/CMakeLists.txt @@ -35,6 +35,7 @@ ament_target_dependencies(${PROJECT_NAME} "rosidl_generator_c" "rosidl_generator_cpp") +configure_rclcpp(${PROJECT_NAME}) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. target_compile_definitions(${PROJECT_NAME} diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 0ce4b4a948..ba5ca962fa 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -54,14 +54,12 @@ class ClientBaseImpl; * * Internally, this class is responsible for interfacing with the `rcl_action` API. */ -class ClientBase : public rclcpp::Waitable +class RCLCPP_ACTION_PUBLIC ClientBase : public rclcpp::Waitable { public: - RCLCPP_ACTION_PUBLIC virtual ~ClientBase(); /// Return true if there is an action server that is ready to take goal requests. - RCLCPP_ACTION_PUBLIC bool action_server_is_ready() const; @@ -80,42 +78,34 @@ class ClientBase : public rclcpp::Waitable // Waitables API /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_subscriptions() override; /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_timers() override; /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_clients() override; /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services() override; /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_guard_conditions() override; /// \internal - RCLCPP_ACTION_PUBLIC bool add_to_wait_set(rcl_wait_set_t * wait_set) override; /// \internal - RCLCPP_ACTION_PUBLIC bool is_ready(rcl_wait_set_t * wait_set) override; /// \internal - RCLCPP_ACTION_PUBLIC void execute() override; @@ -123,7 +113,6 @@ class ClientBase : public rclcpp::Waitable // ----------------- protected: - RCLCPP_ACTION_PUBLIC ClientBase( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, @@ -133,7 +122,6 @@ class ClientBase : public rclcpp::Waitable const rcl_action_client_options_t & options); /// Wait for action_server_is_ready() to become true, or until the given timeout is reached. - RCLCPP_ACTION_PUBLIC bool wait_for_action_server_nanoseconds(std::chrono::nanoseconds timeout); @@ -142,17 +130,14 @@ class ClientBase : public rclcpp::Waitable using ResponseCallback = std::function response)>; /// \internal - RCLCPP_ACTION_PUBLIC rclcpp::Logger get_logger(); /// \internal - RCLCPP_ACTION_PUBLIC virtual GoalID generate_goal_id(); /// \internal - RCLCPP_ACTION_PUBLIC virtual void send_goal_request( @@ -160,7 +145,6 @@ class ClientBase : public rclcpp::Waitable ResponseCallback callback); /// \internal - RCLCPP_ACTION_PUBLIC virtual void send_result_request( @@ -168,7 +152,6 @@ class ClientBase : public rclcpp::Waitable ResponseCallback callback); /// \internal - RCLCPP_ACTION_PUBLIC virtual void send_cancel_request( @@ -181,7 +164,6 @@ class ClientBase : public rclcpp::Waitable create_goal_response() const = 0; /// \internal - RCLCPP_ACTION_PUBLIC virtual void handle_goal_response( @@ -194,7 +176,6 @@ class ClientBase : public rclcpp::Waitable create_result_response() const = 0; /// \internal - RCLCPP_ACTION_PUBLIC virtual void handle_result_response( @@ -207,7 +188,6 @@ class ClientBase : public rclcpp::Waitable create_cancel_response() const = 0; /// \internal - RCLCPP_ACTION_PUBLIC virtual void handle_cancel_response( diff --git a/rclcpp_action/include/rclcpp_action/server.hpp b/rclcpp_action/include/rclcpp_action/server.hpp index b1bb47a4f8..6129d94314 100644 --- a/rclcpp_action/include/rclcpp_action/server.hpp +++ b/rclcpp_action/include/rclcpp_action/server.hpp @@ -67,10 +67,9 @@ enum class CancelResponse : int8_t * * Internally, this class is responsible for interfacing with the `rcl_action` API. */ -class ServerBase : public rclcpp::Waitable +class RCLCPP_ACTION_PUBLIC ServerBase : public rclcpp::Waitable { public: - RCLCPP_ACTION_PUBLIC virtual ~ServerBase(); // ------------- @@ -78,49 +77,41 @@ class ServerBase : public rclcpp::Waitable /// Return the number of subscriptions used to implement an action server /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_subscriptions() override; /// Return the number of timers used to implement an action server /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_timers() override; /// Return the number of service clients used to implement an action server /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_clients() override; /// Return the number of service servers used to implement an action server /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services() override; /// Return the number of guard conditions used to implement an action server /// \internal - RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_guard_conditions() override; /// Add all entities to a wait set. /// \internal - RCLCPP_ACTION_PUBLIC bool add_to_wait_set(rcl_wait_set_t * wait_set) override; /// Return true if any entity belonging to the action server is ready to be executed. /// \internal - RCLCPP_ACTION_PUBLIC bool is_ready(rcl_wait_set_t *) override; /// Act on entities in the wait set which are ready to be acted upon. /// \internal - RCLCPP_ACTION_PUBLIC void execute() override; @@ -128,7 +119,6 @@ class ServerBase : public rclcpp::Waitable // ----------------- protected: - RCLCPP_ACTION_PUBLIC ServerBase( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock, @@ -143,7 +133,6 @@ class ServerBase : public rclcpp::Waitable // ServerBase will call this function when a goal request is received. // The subclass should convert to the real type and call a user's callback. /// \internal - RCLCPP_ACTION_PUBLIC virtual std::pair> call_handle_goal_callback(GoalID &, std::shared_ptr request) = 0; @@ -152,28 +141,24 @@ class ServerBase : public rclcpp::Waitable // each goal id. // The subclass should look up a goal handle and call the user's callback. /// \internal - RCLCPP_ACTION_PUBLIC virtual CancelResponse call_handle_cancel_callback(const GoalID & uuid) = 0; /// Given a goal request message, return the UUID contained within. /// \internal - RCLCPP_ACTION_PUBLIC virtual GoalID get_goal_id_from_goal_request(void * message) = 0; /// Create an empty goal request message so it can be taken from a lower layer. /// \internal - RCLCPP_ACTION_PUBLIC virtual std::shared_ptr create_goal_request() = 0; /// Call user callback to inform them a goal has been accepted. /// \internal - RCLCPP_ACTION_PUBLIC virtual void call_goal_accepted_callback( @@ -182,42 +167,35 @@ class ServerBase : public rclcpp::Waitable /// Given a result request message, return the UUID contained within. /// \internal - RCLCPP_ACTION_PUBLIC virtual GoalID get_goal_id_from_result_request(void * message) = 0; /// Create an empty goal request message so it can be taken from a lower layer. /// \internal - RCLCPP_ACTION_PUBLIC virtual std::shared_ptr create_result_request() = 0; /// Create an empty goal result message so it can be sent as a reply in a lower layer /// \internal - RCLCPP_ACTION_PUBLIC virtual std::shared_ptr create_result_response(decltype(action_msgs::msg::GoalStatus::status) status) = 0; /// \internal - RCLCPP_ACTION_PUBLIC void publish_status(); /// \internal - RCLCPP_ACTION_PUBLIC void notify_goal_terminal_state(); /// \internal - RCLCPP_ACTION_PUBLIC void publish_result(const GoalID & uuid, std::shared_ptr result_msg); /// \internal - RCLCPP_ACTION_PUBLIC void publish_feedback(std::shared_ptr feedback_msg); @@ -227,25 +205,21 @@ class ServerBase : public rclcpp::Waitable private: /// Handle a request to add a new goal to the server /// \internal - RCLCPP_ACTION_PUBLIC void execute_goal_request_received(); /// Handle a request to cancel goals on the server /// \internal - RCLCPP_ACTION_PUBLIC void execute_cancel_request_received(); /// Handle a request to get the result of an action /// \internal - RCLCPP_ACTION_PUBLIC void execute_result_request_received(); /// Handle a timeout indicating a completed goal should be forgotten by the server /// \internal - RCLCPP_ACTION_PUBLIC void execute_check_expired_goals(); diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index 5b06fc6059..a26c6efe63 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -39,28 +39,24 @@ namespace rclcpp_action * * Internally, this class is responsible for interfacing with the `rcl_action` API. */ -class ServerGoalHandleBase +class RCLCPP_ACTION_PUBLIC ServerGoalHandleBase { public: /// Indicate if client has requested this goal be cancelled. /// \return true if a cancelation request has been accepted for this goal. - RCLCPP_ACTION_PUBLIC bool is_canceling() const; /// Indicate if goal is pending or executing. /// \return false if goal has reached a terminal state. - RCLCPP_ACTION_PUBLIC bool is_active() const; /// Indicate if goal is executing. /// \return true only if the goal is in an executing state. - RCLCPP_ACTION_PUBLIC bool is_executing() const; - RCLCPP_ACTION_PUBLIC virtual ~ServerGoalHandleBase(); @@ -69,7 +65,6 @@ class ServerGoalHandleBase // API for communication between ServerGoalHandleBase and ServerGoalHandle<> /// \internal - RCLCPP_ACTION_PUBLIC ServerGoalHandleBase( std::shared_ptr rcl_handle ) @@ -78,33 +73,27 @@ class ServerGoalHandleBase } /// \internal - RCLCPP_ACTION_PUBLIC void _set_aborted(); /// \internal - RCLCPP_ACTION_PUBLIC void _set_succeeded(); /// \internal - RCLCPP_ACTION_PUBLIC void _set_canceling(); /// \internal - RCLCPP_ACTION_PUBLIC void _set_canceled(); /// \internal - RCLCPP_ACTION_PUBLIC void _set_executing(); /// Transition the goal to canceled state if it never reached a terminal state. /// \internal - RCLCPP_ACTION_PUBLIC bool try_canceling() noexcept; diff --git a/rclcpp_lifecycle/CMakeLists.txt b/rclcpp_lifecycle/CMakeLists.txt index 10bc512848..879c64e99a 100644 --- a/rclcpp_lifecycle/CMakeLists.txt +++ b/rclcpp_lifecycle/CMakeLists.txt @@ -33,6 +33,7 @@ ament_target_dependencies(rclcpp_lifecycle "rosidl_typesupport_cpp" ) +configure_rclcpp(${PROJECT_NAME}) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. target_compile_definitions(rclcpp_lifecycle PRIVATE "RCLCPP_LIFECYCLE_BUILDING_DLL") diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 22b98a98c2..7323b6f3ae 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -66,7 +66,7 @@ namespace rclcpp_lifecycle /** * has lifecycle nodeinterface for configuring this node. */ -class LifecycleNode : public node_interfaces::LifecycleNodeInterface, +class RCLCPP_LIFECYCLE_PUBLIC LifecycleNode : public node_interfaces::LifecycleNodeInterface, public std::enable_shared_from_this { public: @@ -78,7 +78,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * \param[in] namespace_ Namespace of the node. * \param[in] options Additional options to control creation of the node. */ - RCLCPP_LIFECYCLE_PUBLIC explicit LifecycleNode( const std::string & node_name, const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); @@ -90,40 +89,33 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * \param[in] context The context for the node (usually represents the state of a process). * \param[in] options Additional options to control creation of the node. */ - RCLCPP_LIFECYCLE_PUBLIC LifecycleNode( const std::string & node_name, const std::string & namespace_, const rclcpp::NodeOptions & options); - RCLCPP_LIFECYCLE_PUBLIC virtual ~LifecycleNode(); /// Get the name of the node. // \return The name of the node. - RCLCPP_LIFECYCLE_PUBLIC const char * get_name() const; /// Get the namespace of the node. // \return The namespace of the node. - RCLCPP_LIFECYCLE_PUBLIC const char * get_namespace() const; /// Get the logger of the node. /** \return The logger of the node. */ - RCLCPP_LIFECYCLE_PUBLIC rclcpp::Logger get_logger() const; /// Create and return a callback group. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::callback_group::CallbackGroup::SharedPtr create_callback_group(rclcpp::callback_group::CallbackGroupType group_type); /// Return the list of callback groups in the node. - RCLCPP_LIFECYCLE_PUBLIC const std::vector & get_callback_groups() const; @@ -246,23 +238,18 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); - RCLCPP_LIFECYCLE_PUBLIC std::vector set_parameters(const std::vector & parameters); - RCLCPP_LIFECYCLE_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector & parameters); - RCLCPP_LIFECYCLE_PUBLIC std::vector get_parameters(const std::vector & names) const; - RCLCPP_LIFECYCLE_PUBLIC rclcpp::Parameter get_parameter(const std::string & name) const; - RCLCPP_LIFECYCLE_PUBLIC bool get_parameter( const std::string & name, @@ -272,15 +259,12 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, bool get_parameter(const std::string & name, ParameterT & parameter) const; - RCLCPP_LIFECYCLE_PUBLIC std::vector describe_parameters(const std::vector & names) const; - RCLCPP_LIFECYCLE_PUBLIC std::vector get_parameter_types(const std::vector & names) const; - RCLCPP_LIFECYCLE_PUBLIC rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const; @@ -293,23 +277,18 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, void register_param_change_callback(CallbackT && callback); - RCLCPP_LIFECYCLE_PUBLIC std::vector get_node_names() const; - RCLCPP_LIFECYCLE_PUBLIC std::map> get_topic_names_and_types(bool no_demangle = false) const; - RCLCPP_LIFECYCLE_PUBLIC std::map> get_service_names_and_types() const; - RCLCPP_LIFECYCLE_PUBLIC size_t count_publishers(const std::string & topic_name) const; - RCLCPP_LIFECYCLE_PUBLIC size_t count_subscribers(const std::string & topic_name) const; @@ -318,7 +297,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * The Event object is scoped and therefore to return the load just let it go * out of scope. */ - RCLCPP_LIFECYCLE_PUBLIC rclcpp::Event::SharedPtr get_graph_event(); @@ -329,72 +307,58 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * \throws EventNotRegisteredError if the given event was not acquired with * get_graph_event(). */ - RCLCPP_LIFECYCLE_PUBLIC void wait_for_graph_change( rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout); - RCLCPP_LIFECYCLE_PUBLIC rclcpp::Clock::SharedPtr get_clock(); - RCLCPP_LIFECYCLE_PUBLIC rclcpp::Time now(); /// Return the Node's internal NodeBaseInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface(); /// Return the Node's internal NodeClockInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface(); /// Return the Node's internal NodeGraphInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface(); /// Return the Node's internal NodeTimersInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface(); /// Return the Node's internal NodeTopicsInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface(); /// Return the Node's internal NodeServicesInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface(); /// Return the Node's internal NodeParametersInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface(); /// Return the Node's internal NodeWaitablesInterface implementation. - RCLCPP_LIFECYCLE_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface(); // // LIFECYCLE COMPONENTS // - RCLCPP_LIFECYCLE_PUBLIC const State & get_current_state(); - RCLCPP_LIFECYCLE_PUBLIC std::vector get_available_states(); - RCLCPP_LIFECYCLE_PUBLIC std::vector get_available_transitions(); @@ -402,101 +366,78 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, /* * return the new state after this transition */ - RCLCPP_LIFECYCLE_PUBLIC const State & trigger_transition(const Transition & transition); - RCLCPP_LIFECYCLE_PUBLIC const State & trigger_transition( const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC const State & trigger_transition(uint8_t transition_id); - RCLCPP_LIFECYCLE_PUBLIC const State & trigger_transition( uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC const State & configure(); - RCLCPP_LIFECYCLE_PUBLIC const State & configure(LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC const State & cleanup(); - RCLCPP_LIFECYCLE_PUBLIC const State & cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC const State & activate(); - RCLCPP_LIFECYCLE_PUBLIC const State & activate(LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC const State & deactivate(); - RCLCPP_LIFECYCLE_PUBLIC const State & deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC const State & shutdown(); - RCLCPP_LIFECYCLE_PUBLIC const State & shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code); - RCLCPP_LIFECYCLE_PUBLIC bool register_on_configure(std::function fcn); - RCLCPP_LIFECYCLE_PUBLIC bool register_on_cleanup(std::function fcn); - RCLCPP_LIFECYCLE_PUBLIC bool register_on_shutdown(std::function fcn); - RCLCPP_LIFECYCLE_PUBLIC bool register_on_activate(std::function fcn); - RCLCPP_LIFECYCLE_PUBLIC bool register_on_deactivate(std::function fcn); - RCLCPP_LIFECYCLE_PUBLIC bool register_on_error(std::function fcn); protected: - RCLCPP_LIFECYCLE_PUBLIC void add_publisher_handle(std::shared_ptr pub); - RCLCPP_LIFECYCLE_PUBLIC void add_timer_handle(std::shared_ptr timer); private: RCLCPP_DISABLE_COPY(LifecycleNode) - RCLCPP_LIFECYCLE_PUBLIC bool group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group);