From bdf1f8f78a95bb59c4549465300fd0a11867f137 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 17 Jul 2024 11:48:53 +0200 Subject: [PATCH] Removed deprecated methods and classes (#2575) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rclcpp/include/rclcpp/callback_group.hpp | 40 ---- rclcpp/include/rclcpp/client.hpp | 17 -- rclcpp/include/rclcpp/create_client.hpp | 22 +- rclcpp/include/rclcpp/event_handler.hpp | 7 - rclcpp/include/rclcpp/loaned_message.hpp | 30 --- rclcpp/include/rclcpp/node.hpp | 36 ---- rclcpp/include/rclcpp/node_impl.hpp | 33 --- .../node_parameters_interface.hpp | 2 - rclcpp/include/rclcpp/parameter_client.hpp | 163 --------------- rclcpp/include/rclcpp/parameter_service.hpp | 14 -- rclcpp/include/rclcpp/publisher.hpp | 23 --- rclcpp/include/rclcpp/rate.hpp | 85 -------- rclcpp/include/rclcpp/subscription.hpp | 12 -- rclcpp/include/rclcpp/typesupport_helpers.hpp | 19 -- rclcpp/include/rclcpp/waitable.hpp | 51 ----- rclcpp/src/rclcpp/rate.cpp | 6 - rclcpp/src/rclcpp/waitable.cpp | 66 +----- rclcpp/test/rclcpp/test_client.cpp | 42 ---- rclcpp/test/rclcpp/test_loaned_message.cpp | 47 ----- rclcpp/test/rclcpp/test_rate.cpp | 195 ------------------ .../rclcpp_lifecycle/lifecycle_node.hpp | 29 --- .../rclcpp_lifecycle/lifecycle_node_impl.hpp | 25 --- rclcpp_lifecycle/test/test_client.cpp | 43 ---- rclcpp_lifecycle/test/test_service.cpp | 25 --- 24 files changed, 4 insertions(+), 1028 deletions(-) diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index d8c529d56f..b4a4d4e9a6 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -59,46 +59,6 @@ class CallbackGroup public: RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup) - /// Constructor for CallbackGroup. - /** - * Callback Groups have a type, either 'Mutually Exclusive' or 'Reentrant' - * and when creating one the type must be specified. - * - * Callbacks in Reentrant Callback Groups must be able to: - * - run at the same time as themselves (reentrant) - * - run at the same time as other callbacks in their group - * - run at the same time as other callbacks in other groups - * - * Callbacks in Mutually Exclusive Callback Groups: - * - will not be run multiple times simultaneously (non-reentrant) - * - will not be run at the same time as other callbacks in their group - * - but must run at the same time as callbacks in other groups - * - * Additionally, callback groups have a property which determines whether or - * not they are added to an executor with their associated node automatically. - * When creating a callback group the automatically_add_to_executor_with_node - * argument determines this behavior, and if true it will cause the newly - * created callback group to be added to an executor with the node when the - * Executor::add_node method is used. - * If false, this callback group will not be added automatically and would - * have to be added to an executor manually using the - * Executor::add_callback_group method. - * - * Whether the node was added to the executor before creating the callback - * group, or after, is irrelevant; the callback group will be automatically - * added to the executor in either case. - * - * \param[in] group_type The type of the callback group. - * \param[in] automatically_add_to_executor_with_node A boolean that - * determines whether a callback group is automatically added to an executor - * with the node with which it is associated. - */ - [[deprecated("Use CallbackGroup constructor with context function argument")]] - RCLCPP_PUBLIC - explicit CallbackGroup( - CallbackGroupType group_type, - bool automatically_add_to_executor_with_node = true); - /// Constructor for CallbackGroup. /** * Callback Groups have a type, either 'Mutually Exclusive' or 'Reentrant' diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index fb7547b424..ff90dcb346 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -70,14 +70,6 @@ struct FutureAndRequestId /// Allow implicit conversions to `std::future` by reference. operator FutureT &() {return this->future;} - /// Deprecated, use the `future` member variable instead. - /** - * Allow implicit conversions to `std::future` by value. - * \deprecated - */ - [[deprecated("FutureAndRequestId: use .future instead of an implicit conversion")]] - operator FutureT() {return this->future;} - // delegate future like methods in the std::future impl_ /// See std::future::get(). @@ -436,15 +428,6 @@ class Client : public ClientBase { using detail::FutureAndRequestId>::FutureAndRequestId; - /// Deprecated, use `.future.share()` instead. - /** - * Allow implicit conversions to `std::shared_future` by value. - * \deprecated - */ - [[deprecated( - "FutureAndRequestId: use .future.share() instead of an implicit conversion")]] - operator SharedFuture() {return this->future.share();} - // delegate future like methods in the std::future impl_ /// See std::future::share(). diff --git a/rclcpp/include/rclcpp/create_client.hpp b/rclcpp/include/rclcpp/create_client.hpp index 00e6ff3c0e..8cc73c7500 100644 --- a/rclcpp/include/rclcpp/create_client.hpp +++ b/rclcpp/include/rclcpp/create_client.hpp @@ -47,28 +47,9 @@ create_client( const std::string & service_name, const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr) -{ - return create_client( - node_base, node_graph, node_services, - service_name, - qos.get_rmw_qos_profile(), - group); -} - -/// Create a service client with a given type. -/// \internal -template -typename rclcpp::Client::SharedPtr -create_client( - std::shared_ptr node_base, - std::shared_ptr node_graph, - std::shared_ptr node_services, - const std::string & service_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) { rcl_client_options_t options = rcl_client_get_default_options(); - options.qos = qos_profile; + options.qos = qos.get_rmw_qos_profile(); auto cli = rclcpp::Client::make_shared( node_base.get(), @@ -80,7 +61,6 @@ create_client( node_services->add_client(cli_base_ptr, group); return cli; } - } // namespace rclcpp #endif // RCLCPP__CREATE_CLIENT_HPP_ diff --git a/rclcpp/include/rclcpp/event_handler.hpp b/rclcpp/include/rclcpp/event_handler.hpp index 887c571d16..61f198700c 100644 --- a/rclcpp/include/rclcpp/event_handler.hpp +++ b/rclcpp/include/rclcpp/event_handler.hpp @@ -233,8 +233,6 @@ class EventHandlerBase : public Waitable size_t wait_set_event_index_; }; -using QOSEventHandlerBase [[deprecated("Use rclcpp::EventHandlerBase")]] = EventHandlerBase; - template class EventHandler : public EventHandlerBase { @@ -311,11 +309,6 @@ class EventHandler : public EventHandlerBase ParentHandleT parent_handle_; EventCallbackT event_callback_; }; - -template -using QOSEventHandler [[deprecated("Use rclcpp::EventHandler")]] = EventHandler; - } // namespace rclcpp #endif // RCLCPP__EVENT_HANDLER_HPP_ diff --git a/rclcpp/include/rclcpp/loaned_message.hpp b/rclcpp/include/rclcpp/loaned_message.hpp index 6b30e271e0..282fb6c801 100644 --- a/rclcpp/include/rclcpp/loaned_message.hpp +++ b/rclcpp/include/rclcpp/loaned_message.hpp @@ -82,36 +82,6 @@ class LoanedMessage } } - /// Constructor of the LoanedMessage class. - /** - * The constructor of this class allocates memory for a given message type - * and associates this with a given publisher. - * - * Given the publisher instance, a case differentiation is being performaned - * which decides whether the underlying middleware is able to allocate the appropriate - * memory for this message type or not. - * In the case that the middleware can not loan messages, the passed in allocator instance - * is being used to allocate the message within the scope of this class. - * Otherwise, the allocator is being ignored and the allocation is solely performaned - * in the underlying middleware with its appropriate allocation strategy. - * The need for this arises as the user code can be written explicitly targeting a middleware - * capable of loaning messages. - * However, this user code is ought to be usable even when dynamically linked against - * a middleware which doesn't support message loaning in which case the allocator will be used. - * - * \param[in] pub rclcpp::Publisher instance to which the memory belongs - * \param[in] allocator Allocator instance in case middleware can not allocate messages - * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. - */ - [[ - deprecated("used the LoanedMessage constructor that does not use a shared_ptr to the allocator") - ]] - LoanedMessage( - const rclcpp::PublisherBase * pub, - std::shared_ptr> allocator) - : LoanedMessage(*pub, *allocator) - {} - /// Move semantic for RVO LoanedMessage(LoanedMessage && other) : pub_(std::move(other.pub_)), diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 35863abba4..f395bf8ea3 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -257,22 +257,6 @@ class Node : public std::enable_shared_from_this CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Client. - /** - * \param[in] service_name The topic to service on. - * \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client. - * \param[in] group Callback group to call the service. - * \return Shared pointer to the created client. - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - typename rclcpp::Client::SharedPtr - create_client( - const std::string & service_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Client. /** * \param[in] service_name The name on which the service is accessible. @@ -287,24 +271,6 @@ class Node : public std::enable_shared_from_this const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Service. - /** - * \param[in] service_name The topic to service on. - * \param[in] callback User-defined callback function. - * \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client. - * \param[in] group Callback group to call the service. - * \return Shared pointer to the created service. - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - typename rclcpp::Service::SharedPtr - create_service( - const std::string & service_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Service. /** * \param[in] service_name The topic to service on. @@ -1015,8 +981,6 @@ class Node : public std::enable_shared_from_this rclcpp::node_interfaces::OnSetParametersCallbackHandle; using OnSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType; - using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] = - OnSetParametersCallbackType; using PostSetParametersCallbackHandle = rclcpp::node_interfaces::PostSetParametersCallbackHandle; diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index d55a23f9c1..9ca2c42c2d 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -154,22 +154,6 @@ Node::create_client( group); } -template -typename Client::SharedPtr -Node::create_client( - const std::string & service_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) -{ - return rclcpp::create_client( - node_base_, - node_graph_, - node_services_, - extend_name_with_sub_namespace(service_name, this->get_sub_namespace()), - qos_profile, - group); -} - template typename rclcpp::Service::SharedPtr Node::create_service( @@ -187,23 +171,6 @@ Node::create_service( group); } -template -typename rclcpp::Service::SharedPtr -Node::create_service( - const std::string & service_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) -{ - return rclcpp::create_service( - node_base_, - node_services_, - extend_name_with_sub_namespace(service_name, this->get_sub_namespace()), - std::forward(callback), - qos_profile, - group); -} - template std::shared_ptr Node::create_generic_publisher( diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp index 301c1e3214..1cf10c1a97 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp @@ -52,8 +52,6 @@ struct OnSetParametersCallbackHandle std::function< rcl_interfaces::msg::SetParametersResult( const std::vector &)>; - using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] = - OnSetParametersCallbackType; OnSetParametersCallbackType callback; }; diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 7dff6e9ad6..67fbae5054 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -52,37 +52,6 @@ class AsyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient) - /// Create an async parameters client. - /** - * \param[in] node_base_interface The node base interface of the corresponding node. - * \param[in] node_topics_interface Node topic base interface. - * \param[in] node_graph_interface The node graph interface of the corresponding node. - * \param[in] node_services_interface Node service interface. - * \param[in] remote_node_name Name of the remote node - * \param[in] qos_profile The rmw qos profile to use to subscribe - * \param[in] group (optional) The async parameter client will be added to this callback group. - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - RCLCPP_PUBLIC - AsyncParametersClient( - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, - const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, - const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr) - : AsyncParametersClient( - node_base_interface, - node_topics_interface, - node_graph_interface, - node_services_interface, - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)), - group) - {} - /// Create an async parameters client. /** * \param[in] node_base_interface The node base interface of the corresponding node. @@ -103,31 +72,6 @@ class AsyncParametersClient const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Constructor - /** - * \param[in] node The async parameters client will be added to this node. - * \param[in] remote_node_name name of the remote node - * \param[in] qos_profile The rmw qos profile to use to subscribe - * \param[in] group (optional) The async parameter client will be added to this callback group. - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - AsyncParametersClient( - const std::shared_ptr node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr) - : AsyncParametersClient( - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)), - group) - {} - /** * \param[in] node The async parameters client will be added to this node. * \param[in] remote_node_name (optional) name of the remote node @@ -150,31 +94,6 @@ class AsyncParametersClient group) {} - /// Constructor - /** - * \param[in] node The async parameters client will be added to this node. - * \param[in] remote_node_name Name of the remote node - * \param[in] qos_profile The rmw qos profile to use to subscribe - * \param[in] group (optional) The async parameter client will be added to this callback group. - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - AsyncParametersClient( - NodeT * node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr) - : AsyncParametersClient( - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)), - group) - {} - /** * \param[in] node The async parameters client will be added to this node. * \param[in] remote_node_name (optional) name of the remote node @@ -383,19 +302,6 @@ class SyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient) - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - SyncParametersClient( - std::shared_ptr node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) - : SyncParametersClient( - std::make_shared(), - node, - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) - {} - template explicit SyncParametersClient( std::shared_ptr node, @@ -408,23 +314,6 @@ class SyncParametersClient qos_profile) {} - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - SyncParametersClient( - rclcpp::Executor::SharedPtr executor, - std::shared_ptr node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) - : SyncParametersClient( - executor, - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) - {} - template SyncParametersClient( rclcpp::Executor::SharedPtr executor, @@ -441,19 +330,6 @@ class SyncParametersClient qos_profile) {} - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - SyncParametersClient( - NodeT * node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) - : SyncParametersClient( - std::make_shared(), - node, - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) - {} - template explicit SyncParametersClient( NodeT * node, @@ -466,23 +342,6 @@ class SyncParametersClient qos_profile) {} - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - SyncParametersClient( - rclcpp::Executor::SharedPtr executor, - NodeT * node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) - : SyncParametersClient( - executor, - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) - {} - template SyncParametersClient( rclcpp::Executor::SharedPtr executor, @@ -499,28 +358,6 @@ class SyncParametersClient qos_profile) {} - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - RCLCPP_PUBLIC - SyncParametersClient( - rclcpp::Executor::SharedPtr executor, - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, - const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, - const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) - : executor_(executor), node_base_interface_(node_base_interface) - { - async_parameters_client_ = - std::make_shared( - node_base_interface, - node_topics_interface, - node_graph_interface, - node_services_interface, - remote_node_name, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))); - } - RCLCPP_PUBLIC SyncParametersClient( rclcpp::Executor::SharedPtr executor, diff --git a/rclcpp/include/rclcpp/parameter_service.hpp b/rclcpp/include/rclcpp/parameter_service.hpp index a952939aca..54353e9579 100644 --- a/rclcpp/include/rclcpp/parameter_service.hpp +++ b/rclcpp/include/rclcpp/parameter_service.hpp @@ -40,20 +40,6 @@ class ParameterService public: RCLCPP_SMART_PTR_DEFINITIONS(ParameterService) - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - RCLCPP_PUBLIC - ParameterService( - const std::shared_ptr node_base, - const std::shared_ptr node_services, - rclcpp::node_interfaces::NodeParametersInterface * node_params, - const rmw_qos_profile_t & qos_profile) - : ParameterService( - node_base, - node_services, - node_params, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile))) - {} - RCLCPP_PUBLIC ParameterService( const std::shared_ptr node_base, diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 3f02be1e55..4861cd0096 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -96,22 +96,6 @@ class Publisher : public PublisherBase using ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type; using ROSMessageTypeDeleter = allocator::Deleter; - using MessageAllocatorTraits - [[deprecated("use PublishedTypeAllocatorTraits")]] = - PublishedTypeAllocatorTraits; - using MessageAllocator - [[deprecated("use PublishedTypeAllocator")]] = - PublishedTypeAllocator; - using MessageDeleter - [[deprecated("use PublishedTypeDeleter")]] = - PublishedTypeDeleter; - using MessageUniquePtr - [[deprecated("use std::unique_ptr")]] = - std::unique_ptr; - using MessageSharedPtr - [[deprecated("use std::shared_ptr")]] = - std::shared_ptr; - using BufferSharedPtr = typename rclcpp::experimental::buffers::IntraProcessBuffer< ROSMessageType, ROSMessageTypeAllocator, @@ -423,13 +407,6 @@ class Publisher : public PublisherBase } } - [[deprecated("use get_published_type_allocator() or get_ros_message_type_allocator() instead")]] - std::shared_ptr - get_allocator() const - { - return std::make_shared(published_type_allocator_); - } - PublishedTypeAllocator get_published_type_allocator() const { diff --git a/rclcpp/include/rclcpp/rate.hpp b/rclcpp/include/rclcpp/rate.hpp index 5b04b72b81..281ddf9de3 100644 --- a/rclcpp/include/rclcpp/rate.hpp +++ b/rclcpp/include/rclcpp/rate.hpp @@ -39,10 +39,6 @@ class RateBase RCLCPP_PUBLIC virtual bool sleep() = 0; - [[deprecated("use get_type() instead")]] - RCLCPP_PUBLIC - virtual bool is_steady() const = 0; - RCLCPP_PUBLIC virtual rcl_clock_type_t get_type() const = 0; @@ -54,82 +50,6 @@ using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::nanoseconds; -template -class [[deprecated("use rclcpp::Rate class instead of GenericRate")]] GenericRate : public RateBase -{ -public: - RCLCPP_SMART_PTR_DEFINITIONS(GenericRate) - - explicit GenericRate(double rate) - : period_(duration_cast(duration(1.0 / rate))), last_interval_(Clock::now()) - {} - explicit GenericRate(std::chrono::nanoseconds period) - : period_(period), last_interval_(Clock::now()) - {} - - virtual bool - sleep() - { - // Time coming into sleep - auto now = Clock::now(); - // Time of next interval - auto next_interval = last_interval_ + period_; - // Detect backwards time flow - if (now < last_interval_) { - // Best thing to do is to set the next_interval to now + period - next_interval = now + period_; - } - // Calculate the time to sleep - auto time_to_sleep = next_interval - now; - // Update the interval - last_interval_ += period_; - // If the time_to_sleep is negative or zero, don't sleep - if (time_to_sleep <= std::chrono::seconds(0)) { - // If an entire cycle was missed then reset next interval. - // This might happen if the loop took more than a cycle. - // Or if time jumps forward. - if (now > next_interval + period_) { - last_interval_ = now + period_; - } - // Either way do not sleep and return false - return false; - } - // Sleep (will get interrupted by ctrl-c, may not sleep full time) - rclcpp::sleep_for(time_to_sleep); - return true; - } - - [[deprecated("use get_type() instead")]] - virtual bool - is_steady() const - { - return Clock::is_steady; - } - - virtual rcl_clock_type_t get_type() const - { - return Clock::is_steady ? RCL_STEADY_TIME : RCL_SYSTEM_TIME; - } - - virtual void - reset() - { - last_interval_ = Clock::now(); - } - - std::chrono::nanoseconds period() const - { - return period_; - } - -private: - RCLCPP_DISABLE_COPY(GenericRate) - - std::chrono::nanoseconds period_; - using ClockDurationNano = std::chrono::duration; - std::chrono::time_point last_interval_; -}; - class Rate : public RateBase { public: @@ -149,11 +69,6 @@ class Rate : public RateBase virtual bool sleep(); - [[deprecated("use get_type() instead")]] - RCLCPP_PUBLIC - virtual bool - is_steady() const; - RCLCPP_PUBLIC virtual rcl_clock_type_t get_type() const; diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index f8a10a5c27..4e552eb1df 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -90,18 +90,6 @@ class Subscription : public SubscriptionBase using ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type; using ROSMessageTypeDeleter = allocator::Deleter; - using MessageAllocatorTraits [[deprecated("use ROSMessageTypeAllocatorTraits")]] = - ROSMessageTypeAllocatorTraits; - using MessageAllocator [[deprecated("use ROSMessageTypeAllocator")]] = - ROSMessageTypeAllocator; - using MessageDeleter [[deprecated("use ROSMessageTypeDeleter")]] = - ROSMessageTypeDeleter; - - using ConstMessageSharedPtr [[deprecated]] = std::shared_ptr; - using MessageUniquePtr - [[deprecated("use std::unique_ptr instead")]] = - std::unique_ptr; - private: using SubscriptionTopicStatisticsSharedPtr = std::shared_ptr; diff --git a/rclcpp/include/rclcpp/typesupport_helpers.hpp b/rclcpp/include/rclcpp/typesupport_helpers.hpp index c93b318440..7f75a8052b 100644 --- a/rclcpp/include/rclcpp/typesupport_helpers.hpp +++ b/rclcpp/include/rclcpp/typesupport_helpers.hpp @@ -38,25 +38,6 @@ RCLCPP_PUBLIC std::shared_ptr get_typesupport_library(const std::string & type, const std::string & typesupport_identifier); -/// Extract the type support handle from the library. -/** - * The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result. - * - * \deprecated Use get_message_typesupport_handle() instead - * - * \param[in] type The topic type, e.g. "std_msgs/msg/String" - * \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp" - * \param[in] library The shared type support library - * \return A type support handle - */ -[[deprecated("Use `get_message_typesupport_handle` instead")]] -RCLCPP_PUBLIC -const rosidl_message_type_support_t * -get_typesupport_handle( - const std::string & type, - const std::string & typesupport_identifier, - rcpputils::SharedLibrary & library); - /// Extract the message type support handle from the library. /** * The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result. diff --git a/rclcpp/include/rclcpp/waitable.hpp b/rclcpp/include/rclcpp/waitable.hpp index e834765a08..280d79c39d 100644 --- a/rclcpp/include/rclcpp/waitable.hpp +++ b/rclcpp/include/rclcpp/waitable.hpp @@ -101,23 +101,6 @@ class Waitable size_t get_number_of_ready_guard_conditions(); -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Woverloaded-virtual" -#endif - /// Deprecated. - /** - * \sa add_to_wait_set(rcl_wait_set_t &) - */ - [[deprecated("Use add_to_wait_set(rcl_wait_set_t & wait_set) signature")]] - RCLCPP_PUBLIC - virtual - void - add_to_wait_set(rcl_wait_set_t * wait_set); -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif - /// Add the Waitable to a wait set. /** * \param[in] wait_set A handle to the wait set to add the Waitable to. @@ -128,23 +111,6 @@ class Waitable void add_to_wait_set(rcl_wait_set_t & wait_set); -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Woverloaded-virtual" -#endif - /// Deprecated. - /** - * \sa is_ready(const rcl_wait_set_t &) - */ - [[deprecated("Use is_ready(const rcl_wait_set_t & wait_set) signature")]] - RCLCPP_PUBLIC - virtual - bool - is_ready(rcl_wait_set_t * wait_set); -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif - /// Check if the Waitable is ready. /** * The input wait set should be the same that was used in a previously call to @@ -212,23 +178,6 @@ class Waitable std::shared_ptr take_data_by_entity_id(size_t id); -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Woverloaded-virtual" -#endif - /// Deprecated. - /** - * \sa execute(const std::shared_ptr &) - */ - [[deprecated("Use execute(const std::shared_ptr & data) signature")]] - RCLCPP_PUBLIC - virtual - void - execute(std::shared_ptr & data); -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif - /// Execute data that is passed in. /** * Before calling this method, the Waitable should be added to a wait set, diff --git a/rclcpp/src/rclcpp/rate.cpp b/rclcpp/src/rclcpp/rate.cpp index 7c98d6d4fe..083bd223c5 100644 --- a/rclcpp/src/rclcpp/rate.cpp +++ b/rclcpp/src/rclcpp/rate.cpp @@ -71,12 +71,6 @@ Rate::sleep() return true; } -bool -Rate::is_steady() const -{ - return clock_->get_clock_type() == RCL_STEADY_TIME; -} - rcl_clock_type_t Rate::get_type() const { diff --git a/rclcpp/src/rclcpp/waitable.cpp b/rclcpp/src/rclcpp/waitable.cpp index 43b562481c..1ee4f9073f 100644 --- a/rclcpp/src/rclcpp/waitable.cpp +++ b/rclcpp/src/rclcpp/waitable.cpp @@ -87,81 +87,21 @@ Waitable::clear_on_ready_callback() "want to use it and make sure to call it on the waitable destructor."); } -void -Waitable::add_to_wait_set(rcl_wait_set_t * wait_set) -{ - this->add_to_wait_set(*wait_set); -} - -void -Waitable::add_to_wait_set(rcl_wait_set_t & wait_set) -{ -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - this->add_to_wait_set(&wait_set); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif -} - -bool -Waitable::is_ready(rcl_wait_set_t * wait_set) -{ - const rcl_wait_set_t & const_wait_set_ref = *wait_set; - return this->is_ready(const_wait_set_ref); -} - bool Waitable::is_ready(const rcl_wait_set_t & wait_set) { -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - // note this const cast is only required to support a deprecated function - return this->is_ready(&const_cast(wait_set)); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif + return this->is_ready(wait_set); } void -Waitable::execute(std::shared_ptr & data) +Waitable::add_to_wait_set(rcl_wait_set_t & wait_set) { - const std::shared_ptr & const_data = data; - this->execute(const_data); + this->add_to_wait_set(wait_set); } void Waitable::execute(const std::shared_ptr & data) { -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif // note this const cast is only required to support a deprecated function this->execute(const_cast &>(data)); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif } diff --git a/rclcpp/test/rclcpp/test_client.cpp b/rclcpp/test/rclcpp/test_client.cpp index 5c7e5046ab..506d981dd6 100644 --- a/rclcpp/test/rclcpp/test_client.cpp +++ b/rclcpp/test/rclcpp/test_client.cpp @@ -89,31 +89,10 @@ TEST_F(TestClient, construction_and_destruction) { { auto client = node->create_client("service"); } - { - // suppress deprecated function warning - #if !defined(_WIN32) - # pragma GCC diagnostic push - # pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #else // !defined(_WIN32) - # pragma warning(push) - # pragma warning(disable: 4996) - #endif - - auto client = node->create_client( - "service", rmw_qos_profile_services_default); - - // remove warning suppression - #if !defined(_WIN32) - # pragma GCC diagnostic pop - #else // !defined(_WIN32) - # pragma warning(pop) - #endif - } { auto client = node->create_client( "service", rclcpp::ServicesQoS()); } - { ASSERT_THROW( { @@ -123,27 +102,6 @@ TEST_F(TestClient, construction_and_destruction) { } TEST_F(TestClient, construction_with_free_function) { - { - auto client = rclcpp::create_client( - node->get_node_base_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - "service", - rmw_qos_profile_services_default, - nullptr); - } - { - ASSERT_THROW( - { - auto client = rclcpp::create_client( - node->get_node_base_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - "invalid_?service", - rmw_qos_profile_services_default, - nullptr); - }, rclcpp::exceptions::InvalidServiceNameError); - } { auto client = rclcpp::create_client( node->get_node_base_interface(), diff --git a/rclcpp/test/rclcpp/test_loaned_message.cpp b/rclcpp/test/rclcpp/test_loaned_message.cpp index 085f5ef3fd..0623210079 100644 --- a/rclcpp/test/rclcpp/test_loaned_message.cpp +++ b/rclcpp/test/rclcpp/test_loaned_message.cpp @@ -40,53 +40,6 @@ class TestLoanedMessage : public ::testing::Test } }; -TEST_F(TestLoanedMessage, initialize) { - auto node = std::make_shared("loaned_message_test_node"); - auto pub = node->create_publisher("loaned_message_test_topic", 1); - -// suppress deprecated function warning -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - - auto pub_allocator = pub->get_allocator(); - -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - -// suppress deprecated function warning -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - - auto loaned_msg = rclcpp::LoanedMessage(pub.get(), pub_allocator); - -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - - ASSERT_TRUE(loaned_msg.is_valid()); - loaned_msg.get().float32_value = 42.0f; - ASSERT_EQ(42.0f, loaned_msg.get().float32_value); - - SUCCEED(); -} - TEST_F(TestLoanedMessage, loan_from_pub) { auto node = std::make_shared("loaned_message_test_node"); auto pub = node->create_publisher("loaned_message_test_topic", 1); diff --git a/rclcpp/test/rclcpp/test_rate.cpp b/rclcpp/test/rclcpp/test_rate.cpp index b80789c853..86d22cbd94 100644 --- a/rclcpp/test/rclcpp/test_rate.cpp +++ b/rclcpp/test/rclcpp/test_rate.cpp @@ -47,21 +47,6 @@ TEST_F(TestRate, rate_basics) { auto start = std::chrono::system_clock::now(); rclcpp::Rate r(period); EXPECT_EQ(rclcpp::Duration(period), r.period()); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - ASSERT_FALSE(r.is_steady()); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif ASSERT_EQ(RCL_SYSTEM_TIME, r.get_type()); ASSERT_TRUE(r.sleep()); auto one = std::chrono::system_clock::now(); @@ -102,23 +87,6 @@ TEST_F(TestRate, wall_rate_basics) { auto start = std::chrono::steady_clock::now(); rclcpp::WallRate r(period); EXPECT_EQ(rclcpp::Duration(period), r.period()); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - ASSERT_TRUE(r.is_steady()); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif ASSERT_EQ(RCL_STEADY_TIME, r.get_type()); ASSERT_TRUE(r.sleep()); auto one = std::chrono::steady_clock::now(); @@ -150,124 +118,6 @@ TEST_F(TestRate, wall_rate_basics) { EXPECT_GT(epsilon, delta); } -/* - Basic test for the deprecated GenericRate class. - */ -TEST_F(TestRate, generic_rate) { - auto period = std::chrono::milliseconds(100); - auto offset = std::chrono::milliseconds(50); - auto epsilon = std::chrono::milliseconds(1); - double overrun_ratio = 1.5; - - { - auto start = std::chrono::system_clock::now(); - -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - - rclcpp::GenericRate gr(period); - ASSERT_FALSE(gr.is_steady()); - -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - - ASSERT_EQ(gr.get_type(), RCL_SYSTEM_TIME); - EXPECT_EQ(period, gr.period()); - ASSERT_TRUE(gr.sleep()); - auto one = std::chrono::system_clock::now(); - auto delta = one - start; - EXPECT_LT(period, delta + epsilon); - EXPECT_GT(period * overrun_ratio, delta); - - rclcpp::sleep_for(offset); - ASSERT_TRUE(gr.sleep()); - auto two = std::chrono::system_clock::now(); - delta = two - start; - EXPECT_LT(2 * period, delta); - EXPECT_GT(2 * period * overrun_ratio, delta); - - rclcpp::sleep_for(offset); - auto two_offset = std::chrono::system_clock::now(); - gr.reset(); - ASSERT_TRUE(gr.sleep()); - auto three = std::chrono::system_clock::now(); - delta = three - two_offset; - EXPECT_LT(period, delta + epsilon); - EXPECT_GT(period * overrun_ratio, delta); - - rclcpp::sleep_for(offset + period); - auto four = std::chrono::system_clock::now(); - ASSERT_FALSE(gr.sleep()); - auto five = std::chrono::system_clock::now(); - delta = five - four; - ASSERT_TRUE(epsilon > delta); - } - - { - auto start = std::chrono::steady_clock::now(); - -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - - rclcpp::GenericRate gr(period); - ASSERT_TRUE(gr.is_steady()); - -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif - - ASSERT_EQ(gr.get_type(), RCL_STEADY_TIME); - EXPECT_EQ(period, gr.period()); - ASSERT_TRUE(gr.sleep()); - auto one = std::chrono::steady_clock::now(); - auto delta = one - start; - EXPECT_LT(period, delta); - EXPECT_GT(period * overrun_ratio, delta); - - rclcpp::sleep_for(offset); - ASSERT_TRUE(gr.sleep()); - auto two = std::chrono::steady_clock::now(); - delta = two - start; - EXPECT_LT(2 * period, delta + epsilon); - EXPECT_GT(2 * period * overrun_ratio, delta); - - rclcpp::sleep_for(offset); - auto two_offset = std::chrono::steady_clock::now(); - gr.reset(); - ASSERT_TRUE(gr.sleep()); - auto three = std::chrono::steady_clock::now(); - delta = three - two_offset; - EXPECT_LT(period, delta); - EXPECT_GT(period * overrun_ratio, delta); - - rclcpp::sleep_for(offset + period); - auto four = std::chrono::steady_clock::now(); - ASSERT_FALSE(gr.sleep()); - auto five = std::chrono::steady_clock::now(); - delta = five - four; - EXPECT_GT(epsilon, delta); - } -} - TEST_F(TestRate, from_double) { { rclcpp::Rate rate(1.0); @@ -290,59 +140,14 @@ TEST_F(TestRate, from_double) { TEST_F(TestRate, clock_types) { { rclcpp::Rate rate(1.0, std::make_shared(RCL_SYSTEM_TIME)); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - EXPECT_FALSE(rate.is_steady()); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif EXPECT_EQ(RCL_SYSTEM_TIME, rate.get_type()); } { rclcpp::Rate rate(1.0, std::make_shared(RCL_STEADY_TIME)); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - EXPECT_TRUE(rate.is_steady()); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif EXPECT_EQ(RCL_STEADY_TIME, rate.get_type()); } { rclcpp::Rate rate(1.0, std::make_shared(RCL_ROS_TIME)); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - EXPECT_FALSE(rate.is_steady()); -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif EXPECT_EQ(RCL_ROS_TIME, rate.get_type()); } } diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 657ddddc34..d63cc726f9 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -280,19 +280,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Client. - /** - * \sa rclcpp::Node::create_client - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - typename rclcpp::Client::SharedPtr - create_client( - const std::string & service_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Client. /** * \param[in] service_name The name on which the service is accessible. @@ -307,20 +294,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Service. - /** - * \sa rclcpp::Node::create_service - * \deprecated use rclcpp::QoS instead of rmw_qos_profile_t - */ - template - [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]] - typename rclcpp::Service::SharedPtr - create_service( - const std::string & service_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group = nullptr); - /// Create and return a Service. /** * \sa rclcpp::Node::create_service @@ -572,8 +545,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, rclcpp::node_interfaces::OnSetParametersCallbackHandle; using OnSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType; - using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] = - OnSetParametersCallbackType; using PostSetParametersCallbackHandle = rclcpp::node_interfaces::PostSetParametersCallbackHandle; diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index 5ffc8a5f1b..b1e73b6c64 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -120,18 +120,6 @@ LifecycleNode::create_timer( this->node_timers_.get()); } -template -typename rclcpp::Client::SharedPtr -LifecycleNode::create_client( - const std::string & service_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) -{ - return rclcpp::create_client( - node_base_, node_graph_, node_services_, - service_name, qos_profile, group); -} - template typename rclcpp::Client::SharedPtr LifecycleNode::create_client( @@ -144,19 +132,6 @@ LifecycleNode::create_client( service_name, qos, group); } -template -typename rclcpp::Service::SharedPtr -LifecycleNode::create_service( - const std::string & service_name, - CallbackT && callback, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) -{ - return rclcpp::create_service( - node_base_, node_services_, - service_name, std::forward(callback), qos_profile, group); -} - template typename rclcpp::Service::SharedPtr LifecycleNode::create_service( diff --git a/rclcpp_lifecycle/test/test_client.cpp b/rclcpp_lifecycle/test/test_client.cpp index 7ded8e346e..f34d71ebfc 100644 --- a/rclcpp_lifecycle/test/test_client.cpp +++ b/rclcpp_lifecycle/test/test_client.cpp @@ -61,27 +61,6 @@ TEST_F(TestClient, construction_and_destruction) { auto client = node_->create_client("service"); EXPECT_TRUE(client); } - { - // suppress deprecated function warning - #if !defined(_WIN32) - # pragma GCC diagnostic push - # pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #else // !defined(_WIN32) - # pragma warning(push) - # pragma warning(disable: 4996) - #endif - - auto client = node_->create_client( - "service", rmw_qos_profile_services_default); - EXPECT_TRUE(client); - - // remove warning suppression - #if !defined(_WIN32) - # pragma GCC diagnostic pop - #else // !defined(_WIN32) - # pragma warning(pop) - #endif - } { auto client = node_->create_client( "service", rclcpp::ServicesQoS()); @@ -97,28 +76,6 @@ TEST_F(TestClient, construction_and_destruction) { } TEST_F(TestClient, construction_with_free_function) { - { - auto client = rclcpp::create_client( - node_->get_node_base_interface(), - node_->get_node_graph_interface(), - node_->get_node_services_interface(), - "service", - rmw_qos_profile_services_default, - nullptr); - EXPECT_TRUE(client); - } - { - ASSERT_THROW( - { - auto client = rclcpp::create_client( - node_->get_node_base_interface(), - node_->get_node_graph_interface(), - node_->get_node_services_interface(), - "invalid_?service", - rmw_qos_profile_services_default, - nullptr); - }, rclcpp::exceptions::InvalidServiceNameError); - } { auto client = rclcpp::create_client( node_->get_node_base_interface(), diff --git a/rclcpp_lifecycle/test/test_service.cpp b/rclcpp_lifecycle/test/test_service.cpp index b3108a9042..13bc25761d 100644 --- a/rclcpp_lifecycle/test/test_service.cpp +++ b/rclcpp_lifecycle/test/test_service.cpp @@ -68,31 +68,6 @@ TEST_F(TestService, construction_and_destruction) { const rclcpp::ServiceBase * const_service_base = service.get(); EXPECT_NE(nullptr, const_service_base->get_service_handle()); } - { - // suppress deprecated function warning - #if !defined(_WIN32) - # pragma GCC diagnostic push - # pragma GCC diagnostic ignored "-Wdeprecated-declarations" - #else // !defined(_WIN32) - # pragma warning(push) - # pragma warning(disable: 4996) - #endif - - auto service = node->create_service( - "service", callback, rmw_qos_profile_services_default); - - // remove warning suppression - #if !defined(_WIN32) - # pragma GCC diagnostic pop - #else // !defined(_WIN32) - # pragma warning(pop) - #endif - - EXPECT_NE(nullptr, service->get_service_handle()); - const rclcpp::ServiceBase * const_service_base = service.get(); - EXPECT_NE(nullptr, const_service_base->get_service_handle()); - } - { ASSERT_THROW( {