From 14824f930b5042507a637e5581c3a1f1a01fd2a7 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 16 Sep 2019 11:35:41 -0700 Subject: [PATCH] remove features and related code which were deprecated in dashing Signed-off-by: William Woodall --- rclcpp/CMakeLists.txt | 11 -- rclcpp/include/rclcpp/create_publisher.hpp | 30 --- rclcpp/include/rclcpp/create_subscription.hpp | 43 ----- rclcpp/include/rclcpp/node.hpp | 179 +----------------- rclcpp/include/rclcpp/node_impl.hpp | 148 --------------- .../node_interfaces/node_parameters.hpp | 5 - .../node_parameters_interface.hpp | 9 - rclcpp/include/rclcpp/publisher.hpp | 48 ----- rclcpp/include/rclcpp/rclcpp.hpp | 3 +- rclcpp/src/rclcpp/node.cpp | 10 - .../node_interfaces/node_parameters.cpp | 37 ---- rclcpp/src/rclcpp/parameter.cpp | 10 - rclcpp/test/test_local_parameters.cpp | 97 ---------- rclcpp/test/test_publisher.cpp | 35 ---- rclcpp/test/test_subscription.cpp | 34 ---- .../rclcpp_lifecycle/lifecycle_node.hpp | 150 --------------- .../rclcpp_lifecycle/lifecycle_node_impl.hpp | 148 --------------- .../rclcpp_lifecycle/lifecycle_publisher.hpp | 47 ----- rclcpp_lifecycle/src/lifecycle_node.cpp | 10 - 19 files changed, 3 insertions(+), 1051 deletions(-) delete mode 100644 rclcpp/test/test_local_parameters.cpp diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index 3109ed9960..938fdfb032 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -462,17 +462,6 @@ if(BUILD_TESTING) "rcl") target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME}) endif() - - ament_add_gtest(test_local_parameters test/test_local_parameters.cpp) - if(TARGET test_local_parameters) - ament_target_dependencies(test_local_parameters - "rcl_interfaces" - "rmw" - "rosidl_generator_cpp" - "rosidl_typesupport_cpp" - ) - target_link_libraries(test_local_parameters ${PROJECT_NAME}) - endif() endif() ament_package() diff --git a/rclcpp/include/rclcpp/create_publisher.hpp b/rclcpp/include/rclcpp/create_publisher.hpp index 29b11f2185..0e99c374e5 100644 --- a/rclcpp/include/rclcpp/create_publisher.hpp +++ b/rclcpp/include/rclcpp/create_publisher.hpp @@ -29,36 +29,6 @@ namespace rclcpp { -template< - typename MessageT, - typename AllocatorT = std::allocator, - typename PublisherT = ::rclcpp::Publisher> -// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function -[[deprecated("use alternative rclcpp::create_publisher() signatures")]] -std::shared_ptr -create_publisher( - rclcpp::node_interfaces::NodeTopicsInterface * node_topics, - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile, - const PublisherEventCallbacks & event_callbacks, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool use_intra_process_comms, - std::shared_ptr allocator) -{ - auto publisher_options = rcl_publisher_get_default_options(); - publisher_options.qos = qos_profile; - - auto pub = node_topics->create_publisher( - topic_name, - rclcpp::create_publisher_factory(event_callbacks, allocator), - publisher_options, - use_intra_process_comms); - - node_topics->add_publisher(pub, group); - - return std::dynamic_pointer_cast(pub); -} - /// Create and return a publisher of the given MessageT type. /** * The NodeT type only needs to have a method called get_node_topics_interface() diff --git a/rclcpp/include/rclcpp/create_subscription.hpp b/rclcpp/include/rclcpp/create_subscription.hpp index fa11affc7b..7c13d6f643 100644 --- a/rclcpp/include/rclcpp/create_subscription.hpp +++ b/rclcpp/include/rclcpp/create_subscription.hpp @@ -29,49 +29,6 @@ namespace rclcpp { -template< - typename MessageT, - typename CallbackT, - typename AllocatorT, - typename CallbackMessageT, - typename SubscriptionT = rclcpp::Subscription> -// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function -[[deprecated("use alternative rclcpp::create_subscription() signatures")]] -typename std::shared_ptr -create_subscription( - rclcpp::node_interfaces::NodeTopicsInterface * node_topics, - const std::string & topic_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - const SubscriptionEventCallbacks & event_callbacks, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - bool use_intra_process_comms, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - CallbackMessageT, AllocatorT>::SharedPtr - msg_mem_strat, - typename std::shared_ptr allocator) -{ - auto subscription_options = rcl_subscription_get_default_options(); - subscription_options.qos = qos_profile; - subscription_options.ignore_local_publications = ignore_local_publications; - - auto factory = rclcpp::create_subscription_factory - ( - std::forward(callback), - event_callbacks, - msg_mem_strat, - allocator); - - auto sub = node_topics->create_subscription( - topic_name, - factory, - subscription_options, - use_intra_process_comms); - node_topics->add_subscription(sub, group); - return std::dynamic_pointer_cast(sub); -} - /// Create and return a subscription of the given MessageT type. /** * The NodeT type only needs to have a method called get_node_topics_interface() diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 9e17b332e7..e46d2626ba 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -174,7 +174,7 @@ class Node : public std::enable_shared_from_this template< typename MessageT, typename AllocatorT = std::allocator, - typename PublisherT = ::rclcpp::Publisher> + typename PublisherT = rclcpp::Publisher> std::shared_ptr create_publisher( const std::string & topic_name, @@ -183,44 +183,6 @@ class Node : public std::enable_shared_from_this PublisherOptionsWithAllocator() ); - /// Create and return a Publisher. - /** - * \param[in] topic_name The topic for this publisher to publish on. - * \param[in] qos_history_depth The depth of the publisher message queue. - * \param[in] allocator Custom allocator. - * \return Shared pointer to the created publisher. - */ - template< - typename MessageT, - typename AllocatorT = std::allocator, - typename PublisherT = ::rclcpp::Publisher> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]] - std::shared_ptr - create_publisher( - const std::string & topic_name, - size_t qos_history_depth, - std::shared_ptr allocator); - - /// Create and return a Publisher. - /** - * \param[in] topic_name The topic for this publisher to publish on. - * \param[in] qos_profile The quality of service profile to pass on to the rmw implementation. - * \param[in] allocator Optional custom allocator. - * \return Shared pointer to the created publisher. - */ - template< - typename MessageT, - typename AllocatorT = std::allocator, - typename PublisherT = ::rclcpp::Publisher> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]] - std::shared_ptr - create_publisher( - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default, - std::shared_ptr allocator = nullptr); - /// Create and return a Subscription. /** * \param[in] topic_name The topic to subscribe on. @@ -252,80 +214,6 @@ class Node : public std::enable_shared_from_this >::SharedPtr msg_mem_strat = nullptr); - /// Create and return a Subscription. - /** - * \param[in] topic_name The topic to subscribe on. - * \param[in] callback The user-defined callback function. - * \param[in] qos_profile The quality of service profile to pass on to the rmw implementation. - * \param[in] group The callback group for this subscription. NULL for no callback group. - * \param[in] ignore_local_publications True to ignore local publications. - * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. - * \param[in] allocator Optional custom allocator. - * \return Shared pointer to the created subscription. - */ - /* TODO(jacquelinekay): - Windows build breaks when static member function passed as default - argument to msg_mem_strat, nullptr is a workaround. - */ - template< - typename MessageT, - typename CallbackT, - typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::Subscription< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated( - "use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead" - )]] - std::shared_ptr - create_subscription( - const std::string & topic_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, - bool ignore_local_publications = false, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat = nullptr, - std::shared_ptr allocator = nullptr); - - /// Create and return a Subscription. - /** - * \param[in] topic_name The topic to subscribe on. - * \param[in] qos_history_depth The depth of the subscription's incoming message queue. - * \param[in] callback The user-defined callback function. - * \param[in] group The callback group for this subscription. NULL for no callback group. - * \param[in] ignore_local_publications True to ignore local publications. - * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. - * \param[in] allocator Optional custom allocator. - * \return Shared pointer to the created subscription. - */ - /* TODO(jacquelinekay): - Windows build breaks when static member function passed as default - argument to msg_mem_strat, nullptr is a workaround. - */ - template< - typename MessageT, - typename CallbackT, - typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::Subscription< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated( - "use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead" - )]] - std::shared_ptr - create_subscription( - const std::string & topic_name, - CallbackT && callback, - size_t qos_history_depth, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, - bool ignore_local_publications = false, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat = nullptr, - std::shared_ptr allocator = nullptr); - /// Create a timer. /** * \param[in] period Time interval between triggers of the callback. @@ -624,38 +512,6 @@ class Node : public std::enable_shared_from_this rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector & parameters); - /// Set one parameter, unless that parameter has already been set. - /** - * Set the given parameter unless already set. - * - * Deprecated, instead use declare_parameter(). - * - * \param[in] parameters The vector of parameters to be set. - * \return The result of each set action as a vector. - */ - template - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use declare_parameter() instead")]] - void - set_parameter_if_not_set(const std::string & name, const ParameterT & value); - - /// Set a map of parameters with the same prefix. - /** - * For each key in the map, a parameter with a name of "name.key" will be set - * to the value in the map. - * - * Deprecated, instead use declare_parameters(). - * - * \param[in] name The prefix of the parameters to set. - * \param[in] values The parameters to set in the given prefix. - */ - template - [[deprecated("use declare_parameters() instead")]] - void - set_parameters_if_not_set( - const std::string & name, - const std::map & values); - /// Return the parameter by the given name. /** * If the parameter has not been declared, then this method may throw the @@ -799,28 +655,6 @@ class Node : public std::enable_shared_from_this const std::string & prefix, std::map & values) const; - /// Get the parameter value; if not set, set the "alternative value" and store it in the node. - /** - * If the parameter is set, then the "value" argument is assigned the value - * in the parameter. - * If the parameter is not set, then the "value" argument is assigned the "alternative_value", - * and the parameter is set to the "alternative_value" on the node. - * - * Deprecated, instead use declare_parameter()'s return value, or use - * has_parameter() to ensure it exists before getting it. - * - * \param[in] name The name of the parameter to get. - * \param[out] value The output where the value of the parameter should be assigned. - * \param[in] alternative_value Value to be used if the parameter was not set. - */ - template - [[deprecated("use declare_parameter() and its return value instead")]] - void - get_parameter_or_set( - const std::string & name, - ParameterT & value, - const ParameterT & alternative_value); - /// Return the parameter descriptor for the given parameter name. /** * Like get_parameters(), this method may throw the @@ -1006,17 +840,6 @@ class Node : public std::enable_shared_from_this OnParametersSetCallbackType set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback); - /// Register the callback for parameter changes - /** - * \param[in] callback User defined callback function. - * It is expected to atomically set parameters. - * \note Repeated invocations of this function will overwrite previous callbacks. - */ - template - [[deprecated("use set_on_parameters_set_callback() instead")]] - void - register_param_change_callback(CallbackT && callback); - /// Get the fully-qualified names of all available nodes. /** * The fully-qualified name includes the local namespace and name of the node. diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index f5a1dbc9b6..e7c30d596c 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -79,34 +79,6 @@ Node::create_publisher( options); } -template -std::shared_ptr -Node::create_publisher( - const std::string & topic_name, - size_t qos_history_depth, - std::shared_ptr allocator) -{ - PublisherOptionsWithAllocator pub_options; - pub_options.allocator = allocator; - return this->create_publisher( - topic_name, rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), pub_options); -} - -template -std::shared_ptr -Node::create_publisher( - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile, - std::shared_ptr allocator) -{ - rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile)); - qos.get_rmw_qos_profile() = qos_profile; - - PublisherOptionsWithAllocator pub_options; - pub_options.allocator = allocator; - return this->create_publisher(topic_name, qos, pub_options); -} - template< typename MessageT, typename CallbackT, @@ -131,65 +103,6 @@ Node::create_subscription( msg_mem_strat); } -template< - typename MessageT, - typename CallbackT, - typename Alloc, - typename SubscriptionT> -std::shared_ptr -Node::create_subscription( - const std::string & topic_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat, - std::shared_ptr allocator) -{ - rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile)); - qos.get_rmw_qos_profile() = qos_profile; - - SubscriptionOptionsWithAllocator sub_options; - sub_options.callback_group = group; - sub_options.ignore_local_publications = ignore_local_publications; - sub_options.allocator = allocator; - - return this->create_subscription( - topic_name, qos, std::forward(callback), sub_options, msg_mem_strat); -} - -template< - typename MessageT, - typename CallbackT, - typename Alloc, - typename SubscriptionT> -std::shared_ptr -Node::create_subscription( - const std::string & topic_name, - CallbackT && callback, - size_t qos_history_depth, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat, - std::shared_ptr allocator) -{ - SubscriptionOptionsWithAllocator sub_options; - sub_options.callback_group = group; - sub_options.ignore_local_publications = ignore_local_publications; - sub_options.allocator = allocator; - - return this->create_subscription( - topic_name, - rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), - std::forward(callback), - sub_options, - msg_mem_strat); -} - template typename rclcpp::WallTimer::SharedPtr Node::create_wall_timer( @@ -303,44 +216,6 @@ Node::declare_parameters( return result; } -template -void -Node::set_parameter_if_not_set( - const std::string & name, - const ParameterT & value) -{ - if ( - !this->has_parameter(name) || - this->describe_parameter(name).type == PARAMETER_NOT_SET) - { - this->set_parameter(rclcpp::Parameter(name, value)); - } -} - -// this is a partially-specialized version of set_parameter_if_not_set above, -// where our concrete type for ParameterT is std::map, but the to-be-determined -// type is the value in the map. -template -void -Node::set_parameters_if_not_set( - const std::string & name, - const std::map & values) -{ - std::vector params; - - for (const auto & val : values) { - std::string parameter_name = name + "." + val.first; - if ( - !this->has_parameter(parameter_name) || - this->describe_parameter(parameter_name).type == PARAMETER_NOT_SET) - { - params.push_back(rclcpp::Parameter(parameter_name, val.second)); - } - } - - this->set_parameters(params); -} - template bool Node::get_parameter(const std::string & name, ParameterT & parameter) const @@ -393,29 +268,6 @@ Node::get_parameters( return result; } -template -void -Node::get_parameter_or_set( - const std::string & name, - ParameterT & value, - const ParameterT & alternative_value) -{ - std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace()); - - bool got_parameter = get_parameter(sub_name, value); - if (!got_parameter) { - this->set_parameters({rclcpp::Parameter(sub_name, alternative_value), }); - value = alternative_value; - } -} - -template -void -Node::register_param_change_callback(CallbackT && callback) -{ - this->node_parameters_->register_param_change_callback(std::forward(callback)); -} - } // namespace rclcpp #endif // RCLCPP__NODE_IMPL_HPP_ diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp index b114e1be3a..4da6349e30 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp @@ -170,11 +170,6 @@ class NodeParameters : public NodeParametersInterface OnParametersSetCallbackType set_on_parameters_set_callback(OnParametersSetCallbackType callback) override; - [[deprecated("use set_on_parameters_set_callback() instead")]] - RCLCPP_PUBLIC - void - register_param_change_callback(OnParametersSetCallbackType callback) override; - RCLCPP_PUBLIC const std::map & get_parameter_overrides() const override; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp index 79cc3577ef..f1102c0afd 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp @@ -173,9 +173,6 @@ class NodeParametersInterface using OnParametersSetCallbackType = OnSetParametersCallbackHandle::OnParametersSetCallbackType; - using ParametersCallbackFunction [[deprecated("use OnParametersSetCallbackType instead")]] = - OnParametersSetCallbackType; - /// Add a callback for when parameters are being set. /** * \sa rclcpp::Node::add_on_set_parameters_callback @@ -203,12 +200,6 @@ class NodeParametersInterface OnParametersSetCallbackType set_on_parameters_set_callback(OnParametersSetCallbackType callback) = 0; - [[deprecated("use set_on_parameters_set_callback() instead")]] - RCLCPP_PUBLIC - virtual - void - register_param_change_callback(OnParametersSetCallbackType callback) = 0; - /// Return the initial parameter values used by the NodeParameters to override default values. RCLCPP_PUBLIC virtual diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index a0bd342cc9..3357d54646 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -127,18 +127,6 @@ class Publisher : public PublisherBase } } -// Skip deprecated attribute in windows, as it raise a warning in template specialization. -#if !defined(_WIN32) - [[deprecated( - "publishing an unique_ptr is prefered when using intra process communication." - " If using a shared_ptr, use publish(*msg).")]] -#endif - virtual void - publish(const std::shared_ptr & msg) - { - publish(*msg); - } - virtual void publish(const MessageT & msg) { @@ -156,48 +144,12 @@ class Publisher : public PublisherBase this->publish(std::move(unique_msg)); } -// Skip deprecated attribute in windows, as it raise a warning in template specialization. -#if !defined(_WIN32) - [[deprecated( - "Use publish(*msg). Check against nullptr before calling if necessary.")]] -#endif - virtual void - publish(const MessageT * msg) - { - if (!msg) { - throw std::runtime_error("msg argument is nullptr"); - } - return this->publish(*msg); - } - void publish(const rcl_serialized_message_t & serialized_msg) { return this->do_serialized_publish(&serialized_msg); } -// Skip deprecated attribute in windows, as it raise a warning in template specialization. -#if !defined(_WIN32) - [[deprecated( - "Use publish(*serialized_msg). Check against nullptr before calling if necessary.")]] -#endif - void - publish(const rcl_serialized_message_t * serialized_msg) - { - return this->do_serialized_publish(serialized_msg); - } - -// Skip deprecated attribute in windows, as it raise a warning in template specialization. -#if !defined(_WIN32) - [[deprecated( - "Use publish(*serialized_msg). Check against nullptr before calling if necessary.")]] -#endif - void - publish(std::shared_ptr serialized_msg) - { - return this->do_serialized_publish(serialized_msg.get()); - } - std::shared_ptr get_allocator() const { return message_allocator_; diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 698688b6ef..98de3cba55 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -48,7 +48,8 @@ * - rclcpp::Node::get_parameter() * - rclcpp::Node::describe_parameters() * - rclcpp::Node::list_parameters() - * - rclcpp::Node::register_param_change_callback() + * - rclcpp::Node::add_on_set_parameters_callback() + * - rclcpp::Node::remove_on_set_parameters_callback() * - rclcpp::Parameter * - rclcpp::ParameterValue * - rclcpp::AsyncParametersClient diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index 902a5beceb..783a7e106e 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -27,17 +27,7 @@ #include "rclcpp/node_interfaces/node_clock.hpp" #include "rclcpp/node_interfaces/node_graph.hpp" #include "rclcpp/node_interfaces/node_logging.hpp" -// When compiling this file, Windows produces a deprecation warning for the -// deprecated function prototype of NodeParameters::register_param_change_callback(). -// Other compilers do not. -#if defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif #include "rclcpp/node_interfaces/node_parameters.hpp" -#if defined(_WIN32) -# pragma warning(pop) -#endif #include "rclcpp/node_interfaces/node_services.hpp" #include "rclcpp/node_interfaces/node_time_source.hpp" #include "rclcpp/node_interfaces/node_timers.hpp" diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 73978821ee..c7d339932d 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -12,17 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -// When compiling this file, Windows produces a deprecation warning for the -// deprecated function prototype of NodeParameters::register_param_change_callback(). -// Other compilers do not. -#if defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif #include "rclcpp/node_interfaces/node_parameters.hpp" -#if defined(_WIN32) -# pragma warning(pop) -#endif #include @@ -919,33 +909,6 @@ NodeParameters::set_on_parameters_set_callback(OnParametersSetCallbackType callb return existing_callback; } -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif -void -NodeParameters::register_param_change_callback(ParametersCallbackFunction callback) -{ - std::lock_guard lock(mutex_); - - ParameterMutationRecursionGuard guard(parameter_modification_enabled_); - - if (on_parameters_set_callback_) { - RCLCPP_WARN( - node_logging_->get_logger(), - "on_parameters_set_callback already registered, overwriting previous callback"); - } - on_parameters_set_callback_ = callback; -} -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - const std::map & NodeParameters::get_parameter_overrides() const { diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index f9a957617c..673e06ab9b 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -19,17 +19,7 @@ #include #include -// When compiling this file, Windows produces a deprecation warning for the -// deprecated function prototype of NodeParameters::register_param_change_callback(). -// Other compilers do not. -#if defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif #include "rclcpp/node_interfaces/node_parameters.hpp" -#if defined(_WIN32) -# pragma warning(pop) -#endif #include "rclcpp/utilities.hpp" using rclcpp::ParameterType; diff --git a/rclcpp/test/test_local_parameters.cpp b/rclcpp/test/test_local_parameters.cpp deleted file mode 100644 index 4c8412d0b1..0000000000 --- a/rclcpp/test/test_local_parameters.cpp +++ /dev/null @@ -1,97 +0,0 @@ -// Copyright 2018 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 "gtest/gtest.h" - -#include "rclcpp/rclcpp.hpp" - -TEST(test_local_parameters, set_parameter_if_not_set) { - auto node = rclcpp::Node::make_shared( - "test_local_parameters_set_parameter_if_not_set", - rclcpp::NodeOptions().allow_undeclared_parameters(true)); - - { - // try to set a map of parameters - std::map bar_map{ - {"x", 0.5}, - {"y", 1.0}, - }; -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - node->set_parameters_if_not_set("bar", bar_map); -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - double bar_x_value; - ASSERT_TRUE(node->get_parameter("bar.x", bar_x_value)); - EXPECT_EQ(bar_x_value, 0.5); - double bar_y_value; - ASSERT_TRUE(node->get_parameter("bar.y", bar_y_value)); - EXPECT_EQ(bar_y_value, 1.0); - std::map new_map; - ASSERT_TRUE(node->get_parameters("bar", new_map)); - ASSERT_EQ(new_map.size(), 2U); - EXPECT_EQ(new_map["x"], 0.5); - EXPECT_EQ(new_map["y"], 1.0); - } - - { - // try to get a map of parameters that doesn't exist - std::map no_exist_map; - ASSERT_FALSE(node->get_parameters("no_exist", no_exist_map)); - } - - { - // set parameters for a map with different types, then try to get them back as a map -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - node->set_parameter_if_not_set("baz.x", 1.0); - node->set_parameter_if_not_set("baz.y", "hello"); -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - std::map baz_map; - EXPECT_THROW(node->get_parameters("baz", baz_map), rclcpp::ParameterTypeException); - } -} - -int main(int argc, char ** argv) -{ - ::setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - // NOTE: use custom main to ensure that rclcpp::init is called only once - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/rclcpp/test/test_publisher.cpp b/rclcpp/test/test_publisher.cpp index 3794b5e288..d86fdfcc65 100644 --- a/rclcpp/test/test_publisher.cpp +++ b/rclcpp/test/test_publisher.cpp @@ -139,41 +139,6 @@ TEST_F(TestPublisher, various_creation_signatures) { rclcpp::create_publisher(node, "topic", 42, rclcpp::PublisherOptions()); (void)publisher; } - // Now deprecated functions. -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - { - auto publisher = node->create_publisher("topic"); - (void)publisher; - } - { - auto publisher = node->create_publisher( - "topic", - 42, - std::make_shared>()); - (void)publisher; - } - { - auto publisher = node->create_publisher("topic", rmw_qos_profile_default); - (void)publisher; - } - { - auto publisher = node->create_publisher( - "topic", - rmw_qos_profile_default, - std::make_shared>()); - (void)publisher; - } -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif } /* diff --git a/rclcpp/test/test_subscription.cpp b/rclcpp/test/test_subscription.cpp index 7f9bed409b..f3a0db68ed 100644 --- a/rclcpp/test/test_subscription.cpp +++ b/rclcpp/test/test_subscription.cpp @@ -203,40 +203,6 @@ TEST_F(TestSubscription, various_creation_signatures) { node, "topic", 42, cb, rclcpp::SubscriptionOptions()); (void)sub; } - // Now deprecated functions. -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - { - auto sub = node->create_subscription("topic", cb, 42); - (void)sub; - } - { - auto sub = node->create_subscription("topic", cb); - (void)sub; - } - { - auto sub = node->create_subscription("topic", cb, rmw_qos_profile_default); - (void)sub; - } - { - auto sub = - node->create_subscription("topic", cb, rmw_qos_profile_default, nullptr); - (void)sub; - } - { - auto sub = node->create_subscription("topic", cb, 42, nullptr); - (void)sub; - } -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif } /* diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 302cc5c158..fec67c7871 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -170,38 +170,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, create_default_publisher_options() ); - /// Create and return a Publisher. - /** - * \param[in] topic_name The topic for this publisher to publish on. - * \param[in] qos_history_depth The depth of the publisher message queue. - * \param[in] allocator allocator to use during publishing activities. - * \return Shared pointer to the created publisher. - */ - template> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]] - std::shared_ptr> - create_publisher( - const std::string & topic_name, - size_t qos_history_depth, - std::shared_ptr allocator); - - /// Create and return a LifecyclePublisher. - /** - * \param[in] topic_name The topic for this publisher to publish on. - * \param[in] qos_profile The QoS settings for this publisher. - * \param[in] allocator allocator to use during publishing activities. - * \return Shared pointer to the created publisher. - */ - template> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]] - std::shared_ptr> - create_publisher( - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default, - std::shared_ptr allocator = nullptr); - /// Create and return a Subscription. /** * \param[in] topic_name The topic to subscribe on. @@ -232,77 +200,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, >::SharedPtr msg_mem_strat = nullptr); - /// Create and return a Subscription. - /** - * \param[in] topic_name The topic to subscribe on. - * \param[in] callback The user-defined callback function. - * \param[in] qos_profile The quality of service profile to pass on to the rmw implementation. - * \param[in] group The callback group for this subscription. NULL for no callback group. - * \param[in] ignore_local_publications True to ignore local publications. - * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. - * \return Shared pointer to the created subscription. - */ - /* TODO(jacquelinekay): - Windows build breaks when static member function passed as default - argument to msg_mem_strat, nullptr is a workaround. - */ - template< - typename MessageT, - typename CallbackT, - typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::Subscription> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated( - "use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead" - )]] - std::shared_ptr - create_subscription( - const std::string & topic_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, - bool ignore_local_publications = false, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat = nullptr, - std::shared_ptr allocator = nullptr); - - /// Create and return a Subscription. - /** - * \param[in] topic_name The topic to subscribe on. - * \param[in] qos_history_depth The depth of the subscription's incoming message queue. - * \param[in] callback The user-defined callback function. - * \param[in] group The callback group for this subscription. NULL for no callback group. - * \param[in] ignore_local_publications True to ignore local publications. - * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. - * \param[in] allocator allocator to be used during handling of subscription callbacks. - * \return Shared pointer to the created subscription. - */ - /* TODO(jacquelinekay): - Windows build breaks when static member function passed as default - argument to msg_mem_strat, nullptr is a workaround. - */ - template< - typename MessageT, - typename CallbackT, - typename Alloc = std::allocator, - typename SubscriptionT = rclcpp::Subscription> - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated( - "use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead" - )]] - std::shared_ptr - create_subscription( - const std::string & topic_name, - size_t qos_history_depth, - CallbackT && callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications = false, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat = nullptr, - std::shared_ptr allocator = nullptr); - /// Create a timer. /** * \param[in] period Time interval between triggers of the callback. @@ -420,30 +317,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector & parameters); - /// Set one parameter, unless that parameter has already been set. - /** - * \sa rclcpp::Node::set_parameter_if_not_set - */ - template - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use declare_parameter() instead")]] - void - set_parameter_if_not_set( - const std::string & name, - const ParameterT & value); - - /// Set a map of parameters with the same prefix. - /** - * \sa rclcpp::Node::set_parameters_if_not_set - */ - template - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use declare_parameters() instead")]] - void - set_parameters_if_not_set( - const std::string & name, - const std::map & values); - /// Return the parameter by the given name. /** * \sa rclcpp::Node::get_parameter @@ -499,19 +372,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, const std::string & prefix, std::map & values) const; - /// Get the parameter value; if not set, set the "alternative value" and store it in the node. - /** - * \sa rclcpp::Node::get_parameter_or_set - */ - template - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use declare_parameter() and its return value instead")]] - void - get_parameter_or_set( - const std::string & name, - ParameterT & value, - const ParameterT & alternative_value); - /// Return the parameter descriptor for the given parameter name. /** * \sa rclcpp::Node::describe_parameter @@ -556,16 +416,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, set_on_parameters_set_callback( rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback); - /// Register the callback for parameter changes - /** - * \sa rclcpp::Node::register_param_change_callback - */ - template - // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function - [[deprecated("use set_on_parameters_set_callback() instead")]] - void - register_param_change_callback(CallbackT && callback); - RCLCPP_LIFECYCLE_PUBLIC std::vector get_node_names() const; diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index 41d925a75c..68f573b3b8 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -54,40 +54,6 @@ LifecycleNode::create_publisher( options); } -template -std::shared_ptr> -LifecycleNode::create_publisher( - const std::string & topic_name, - size_t qos_history_depth, - std::shared_ptr allocator) -{ - rclcpp::PublisherOptionsWithAllocator options; - options.allocator = allocator; - return this->create_publisher( - topic_name, - rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), - options); -} - -template -std::shared_ptr> -LifecycleNode::create_publisher( - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile, - std::shared_ptr allocator) -{ - rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile)); - qos.get_rmw_qos_profile() = qos_profile; - - rclcpp::PublisherOptionsWithAllocator pub_options; - pub_options.allocator = allocator; - - return this->create_publisher( - topic_name, - qos, - pub_options); -} - // TODO(karsten1987): Create LifecycleSubscriber template< typename MessageT, @@ -113,65 +79,6 @@ LifecycleNode::create_subscription( msg_mem_strat); } -template< - typename MessageT, - typename CallbackT, - typename Alloc, - typename SubscriptionT> -std::shared_ptr -LifecycleNode::create_subscription( - const std::string & topic_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat, - std::shared_ptr allocator) -{ - rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile)); - qos.get_rmw_qos_profile() = qos_profile; - - rclcpp::SubscriptionOptionsWithAllocator sub_options; - sub_options.callback_group = group; - sub_options.ignore_local_publications = ignore_local_publications; - sub_options.allocator = allocator; - - return this->create_subscription( - topic_name, std::forward(callback), qos, sub_options, msg_mem_strat); -} - -template< - typename MessageT, - typename CallbackT, - typename Alloc, - typename SubscriptionT> -std::shared_ptr -LifecycleNode::create_subscription( - const std::string & topic_name, - size_t qos_history_depth, - CallbackT && callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy< - typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr - msg_mem_strat, - std::shared_ptr allocator) -{ - rclcpp::SubscriptionOptionsWithAllocator sub_options; - sub_options.callback_group = group; - sub_options.ignore_local_publications = ignore_local_publications; - sub_options.allocator = allocator; - - return this->create_subscription( - topic_name, - std::forward(callback), - rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), - sub_options, - msg_mem_strat); -} - template typename rclcpp::WallTimer::SharedPtr LifecycleNode::create_wall_timer( @@ -290,47 +197,6 @@ LifecycleNode::get_parameter(const std::string & name, ParameterT & parameter) c return result; } -template -void -LifecycleNode::register_param_change_callback(CallbackT && callback) -{ - this->node_parameters_->set_on_parameters_set_callback(std::forward(callback)); -} - -template -void -LifecycleNode::set_parameter_if_not_set( - const std::string & name, - const ParameterT & value) -{ - rclcpp::Parameter parameter; - if (!this->get_parameter(name, parameter)) { - this->set_parameters({rclcpp::Parameter(name, value), }); - } -} - -// this is a partially-specialized version of set_parameter_if_not_set above, -// where our concrete type for ParameterT is std::map, but the to-be-determined -// type is the value in the map. -template -void -LifecycleNode::set_parameters_if_not_set( - const std::string & name, - const std::map & values) -{ - std::vector params; - - for (const auto & val : values) { - std::string param_name = name + "." + val.first; - rclcpp::Parameter parameter; - if (!this->get_parameter(param_name, parameter)) { - params.push_back(rclcpp::Parameter(param_name, val.second)); - } - } - - this->set_parameters(params); -} - // this is a partially-specialized version of get_parameter above, // where our concrete type for ParameterT is std::map, but the to-be-determined // type is the value in the map. @@ -365,19 +231,5 @@ LifecycleNode::get_parameter_or( return got_parameter; } -template -void -LifecycleNode::get_parameter_or_set( - const std::string & name, - ParameterT & value, - const ParameterT & alternative_value) -{ - bool got_parameter = get_parameter(name, value); - if (!got_parameter) { - this->set_parameters({rclcpp::Parameter(name, alternative_value), }); - value = alternative_value; - } -} - } // namespace rclcpp_lifecycle #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_ diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp index 43d7bf622f..e5d2ada421 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp @@ -113,53 +113,6 @@ class LifecyclePublisher : public LifecyclePublisherInterface, rclcpp::Publisher::publish(msg); } - /// LifecyclePublisher publish function - /** - * The publish function checks whether the communication - * was enabled or disabled and forwards the message - * to the actual rclcpp Publisher base class - */ -// Skip deprecated attribute in windows, as it raise a warning in template specialization. -#if !defined(_WIN32) -// Avoid raising a deprecated warning in template specialization in linux. -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" - [[deprecated( - "publishing an unique_ptr is prefered when using intra process communication." - " If using a shared_ptr, use publish(*msg).")]] -#endif - virtual void - publish(const std::shared_ptr & msg) - { - if (!enabled_) { - RCLCPP_WARN( - logger_, - "Trying to publish message on the topic '%s', but the publisher is not activated", - this->get_topic_name()); - - return; - } - rclcpp::Publisher::publish(*msg); - } - -// Skip deprecated attribute in windows, as it raise a warning in template specialization. -#if !defined(_WIN32) - [[deprecated( - "Use publish(*msg). Check against nullptr before calling if necessary.")]] -#endif - virtual void - publish(const MessageT * msg) - { - if (!msg) { - throw std::runtime_error("msg argument is nullptr"); - } - this->publish(*msg); - } - -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#endif - virtual void on_activate() { diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index edecd8d31f..90e7f1cd1d 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -31,17 +31,7 @@ #include "rclcpp/node_interfaces/node_clock.hpp" #include "rclcpp/node_interfaces/node_graph.hpp" #include "rclcpp/node_interfaces/node_logging.hpp" -// When compiling this file, Windows produces a deprecation warning for the -// deprecated function prototype of NodeParameters::register_param_change_callback(). -// Other compilers do not. -#if defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif #include "rclcpp/node_interfaces/node_parameters.hpp" -#if defined(_WIN32) -# pragma warning(pop) -#endif #include "rclcpp/node_interfaces/node_services.hpp" #include "rclcpp/node_interfaces/node_time_source.hpp" #include "rclcpp/node_interfaces/node_timers.hpp"