diff --git a/rclcpp/include/rclcpp/any_subscription_callback.hpp b/rclcpp/include/rclcpp/any_subscription_callback.hpp index 56af35c518..ea26fad397 100644 --- a/rclcpp/include/rclcpp/any_subscription_callback.hpp +++ b/rclcpp/include/rclcpp/any_subscription_callback.hpp @@ -354,12 +354,6 @@ class AnySubscriptionCallback allocator::set_allocator_for_deleter(&ros_message_type_deleter_, &ros_message_type_allocator_); } - [[deprecated("use AnySubscriptionCallback(const AllocatorT & allocator) instead")]] - explicit - AnySubscriptionCallback(std::shared_ptr allocator) // NOLINT[runtime/explicit] - : AnySubscriptionCallback(*NotNull(allocator.get(), "invalid allocator").pointer) - {} - AnySubscriptionCallback(const AnySubscriptionCallback &) = default; /// Generic function for setting the callback. diff --git a/rclcpp/include/rclcpp/duration.hpp b/rclcpp/include/rclcpp/duration.hpp index c6b790fc7a..28b3718660 100644 --- a/rclcpp/include/rclcpp/duration.hpp +++ b/rclcpp/include/rclcpp/duration.hpp @@ -38,13 +38,6 @@ class RCLCPP_PUBLIC Duration */ Duration(int32_t seconds, uint32_t nanoseconds); - /// Construct duration from the specified nanoseconds. - [[deprecated( - "Use Duration::from_nanoseconds instead or std::chrono_literals. For example:" - "rclcpp::Duration::from_nanoseconds(int64_variable);" - "rclcpp::Duration(0ns);")]] - explicit Duration(rcl_duration_value_t nanoseconds); - /// Construct duration from the specified std::chrono::nanoseconds. explicit Duration(std::chrono::nanoseconds nanoseconds); diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 2150f60e1c..65b8797716 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -395,22 +395,6 @@ class Node : public std::enable_shared_from_this rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override = false); - /// Declare a parameter - [[deprecated( - "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \ - "If you want to declare a parameter that won't change type without a default value use:\n" \ - "`node->declare_parameter(name)`, where e.g. ParameterT=int64_t.\n\n" \ - "If you want to declare a parameter that can dynamically change type use:\n" \ - "```\n" \ - "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \ - "descriptor.dynamic_typing = true;\n" \ - "node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \ - "```" - )]] - RCLCPP_PUBLIC - const rclcpp::ParameterValue & - declare_parameter(const std::string & name); - /// Declare and initialize a parameter with a type. /** * See the non-templated declare_parameter() on this class for details. diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp index 552fbc6979..6f0d5b0ed2 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp @@ -103,25 +103,6 @@ class NodeParameters : public NodeParametersInterface virtual ~NodeParameters(); -// This is overriding a deprecated method, so we need to ignore the deprecation warning here. -// Users of the method will still get a warning! -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - [[deprecated(RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE)]] - RCLCPP_PUBLIC - const rclcpp::ParameterValue & - declare_parameter(const std::string & name) override; -#ifndef _WIN32 -# pragma GCC diagnostic pop -#else -# pragma warning(pop) -#endif - RCLCPP_PUBLIC const rclcpp::ParameterValue & declare_parameter( diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp index d9981516c7..743c1b8d4f 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp @@ -45,17 +45,6 @@ struct OnSetParametersCallbackHandle OnParametersSetCallbackType callback; }; -#define RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE \ - "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \ - "If you want to declare a parameter that won't change type without a default value use:\n" \ - "`node_params->declare_parameter(name, type)`, with e.g. type=rclcpp::PARAMETER_INTEGER.\n\n" \ - "If you want to declare a parameter that can dynamically change type use:\n" \ - "```\n" \ - "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \ - "descriptor.dynamic_typing = true;\n" \ - "node_params->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \ - "```" - /// Pure virtual interface class for the NodeParameters part of the Node API. class NodeParametersInterface { @@ -66,15 +55,6 @@ class NodeParametersInterface virtual ~NodeParametersInterface() = default; - /// Declare a parameter. - /** - * \sa rclcpp::Node::declare_parameter - */ - [[deprecated(RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE)]] - virtual - const rclcpp::ParameterValue & - declare_parameter(const std::string & name) = 0; - /// Declare and initialize a parameter. /** * \sa rclcpp::Node::declare_parameter diff --git a/rclcpp/src/rclcpp/duration.cpp b/rclcpp/src/rclcpp/duration.cpp index 6c20757d46..2966cc4899 100644 --- a/rclcpp/src/rclcpp/duration.cpp +++ b/rclcpp/src/rclcpp/duration.cpp @@ -37,11 +37,6 @@ Duration::Duration(int32_t seconds, uint32_t nanoseconds) rcl_duration_.nanoseconds += nanoseconds; } -Duration::Duration(rcl_duration_value_t nanoseconds) -{ - rcl_duration_.nanoseconds = nanoseconds; -} - Duration::Duration(std::chrono::nanoseconds nanoseconds) { rcl_duration_.nanoseconds = nanoseconds.count(); diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index 140fa5f993..8107458f43 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -310,24 +310,6 @@ Node::create_callback_group( return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node); } -const rclcpp::ParameterValue & -Node::declare_parameter(const std::string & name) -{ -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - return this->node_parameters_->declare_parameter(name); -#ifndef _WIN32 -# pragma GCC diagnostic pop -#else -# pragma warning(pop) -#endif -} - const rclcpp::ParameterValue & Node::declare_parameter( const std::string & name, diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 6a76f8b523..aeaaa9a439 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -467,14 +467,6 @@ declare_parameter_helper( return parameters.at(name).value; } -const rclcpp::ParameterValue & -NodeParameters::declare_parameter(const std::string & name) -{ - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.dynamic_typing = true; - return this->declare_parameter(name, rclcpp::ParameterValue{}, descriptor, false); -} - const rclcpp::ParameterValue & NodeParameters::declare_parameter( const std::string & name, diff --git a/rclcpp/test/rclcpp/test_any_subscription_callback.cpp b/rclcpp/test/rclcpp/test_any_subscription_callback.cpp index 02daee010b..4fd3f32626 100644 --- a/rclcpp/test/rclcpp/test_any_subscription_callback.cpp +++ b/rclcpp/test/rclcpp/test_any_subscription_callback.cpp @@ -84,35 +84,6 @@ class TestAnySubscriptionCallbackTA : public ::testing::Test rclcpp::MessageInfo message_info_; }; -void construct_with_null_allocator() -{ -// 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 - - // We need to wrap this in a function because `EXPECT_THROW` is a macro, and thinks - // that the comma in here splits macro arguments, not the template arguments. - rclcpp::AnySubscriptionCallback any_subscription_callback(nullptr); - -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif -} - -TEST(AnySubscriptionCallback, null_allocator) { - EXPECT_THROW( - construct_with_null_allocator(), - std::invalid_argument); -} - TEST_F(TestAnySubscriptionCallback, construct_destruct) { // Default constructor. rclcpp::AnySubscriptionCallback asc1; diff --git a/rclcpp/test/rclcpp/test_node.cpp b/rclcpp/test/rclcpp/test_node.cpp index 7b4bade94b..58af342561 100644 --- a/rclcpp/test/rclcpp/test_node.cpp +++ b/rclcpp/test/rclcpp/test_node.cpp @@ -3138,20 +3138,4 @@ TEST_F(TestNode, static_and_dynamic_typing) { "uninitialized_not_valid_except_dynamic_typing", rclcpp::ParameterValue{}), rclcpp::exceptions::InvalidParameterTypeException); } - { -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - auto param = node->declare_parameter("deprecated_way_dynamic_typing"); - EXPECT_EQ(param, rclcpp::ParameterValue{}); -#ifndef _WIN32 -# pragma GCC diagnostic pop -#else -# pragma warning(pop) -#endif - } } diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 5eac5419f1..a9bf2a5008 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -342,107 +342,13 @@ class Client : public ClientBase using Feedback = typename ActionT::Feedback; using GoalHandle = ClientGoalHandle; using WrappedResult = typename GoalHandle::WrappedResult; + using GoalResponseCallback = std::function; using FeedbackCallback = typename GoalHandle::FeedbackCallback; using ResultCallback = typename GoalHandle::ResultCallback; using CancelRequest = typename ActionT::Impl::CancelGoalService::Request; using CancelResponse = typename ActionT::Impl::CancelGoalService::Response; using CancelCallback = std::function; - /// Compatibility wrapper for `goal_response_callback`. - class GoalResponseCallback - { -public: - using NewSignature = std::function; - using OldSignature = std::function)>; - - GoalResponseCallback() = default; - - GoalResponseCallback(std::nullptr_t) {} // NOLINT, intentionally implicit. - - // implicit constructor - [[deprecated( - "Use new goal response callback signature " - "`std::function::GoalHandle::SharedPtr)>` " - "instead of the old " - "`std::function::GoalHandle::SharedPtr>)>`.\n" - "e.g.:\n" - "```cpp\n" - "Client::SendGoalOptions options;\n" - "options.goal_response_callback = [](Client::GoalHandle::SharedPtr goal) {\n" - " // do something with `goal` here\n" - "};")]] - GoalResponseCallback(OldSignature old_callback) // NOLINT, intentionally implicit. - : old_callback_(std::move(old_callback)) {} - - GoalResponseCallback(NewSignature new_callback) // NOLINT, intentionally implicit. - : new_callback_(std::move(new_callback)) {} - - GoalResponseCallback & - operator=(OldSignature old_callback) {old_callback_ = std::move(old_callback); return *this;} - - GoalResponseCallback & - operator=(NewSignature new_callback) {new_callback_ = std::move(new_callback); return *this;} - - void - operator()(typename GoalHandle::SharedPtr goal_handle) const - { - if (new_callback_) { - new_callback_(std::move(goal_handle)); - return; - } - if (old_callback_) { - throw std::runtime_error{ - "Cannot call GoalResponseCallback(GoalHandle::SharedPtr) " - "if using the old goal response callback signature."}; - } - throw std::bad_function_call{}; - } - - [[deprecated( - "Calling " - "`void goal_response_callback(" - " std::shared_future::GoalHandle::SharedPtr> goal_handle_shared_future)`" - " is deprecated.")]] - void - operator()(std::shared_future goal_handle_future) const - { - if (old_callback_) { - old_callback_(std::move(goal_handle_future)); - return; - } - if (new_callback_) { - new_callback_(std::move(goal_handle_future).get_future().share()); - return; - } - throw std::bad_function_call{}; - } - - explicit operator bool() const noexcept { - return new_callback_ || old_callback_; - } - -private: - friend class Client; - void - operator()( - typename GoalHandle::SharedPtr goal_handle, - std::shared_future goal_handle_future) const - { - if (new_callback_) { - new_callback_(std::move(goal_handle)); - return; - } - if (old_callback_) { - old_callback_(std::move(goal_handle_future)); - return; - } - throw std::bad_function_call{}; - } - - NewSignature new_callback_; - OldSignature old_callback_; - }; - /// Options for sending a goal. /** * This struct is used to pass parameters to the function `async_send_goal`. @@ -524,14 +430,14 @@ class Client : public ClientBase goal_request->goal = goal; this->send_goal_request( std::static_pointer_cast(goal_request), - [this, goal_request, options, promise, future](std::shared_ptr response) mutable + [this, goal_request, options, promise](std::shared_ptr response) mutable { using GoalResponse = typename ActionT::Impl::SendGoalService::Response; auto goal_response = std::static_pointer_cast(response); if (!goal_response->accepted) { promise->set_value(nullptr); if (options.goal_response_callback) { - options.goal_response_callback(nullptr, future); + options.goal_response_callback(nullptr); } return; } @@ -547,7 +453,7 @@ class Client : public ClientBase } promise->set_value(goal_handle); if (options.goal_response_callback) { - options.goal_response_callback(goal_handle, future); + options.goal_response_callback(goal_handle); } if (options.result_callback) { diff --git a/rclcpp_action/test/test_client.cpp b/rclcpp_action/test/test_client.cpp index b99aa236bd..b94a82d500 100644 --- a/rclcpp_action/test/test_client.cpp +++ b/rclcpp_action/test/test_client.cpp @@ -536,64 +536,6 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_goal_response_callback_wait } } -TEST_F(TestClientAgainstServer, async_send_goal_with_deprecated_goal_response_callback) -{ - auto action_client = rclcpp_action::create_client(client_node, action_name); - ASSERT_TRUE(action_client->wait_for_action_server(WAIT_FOR_SERVER_TIMEOUT)); - - bool goal_response_received = false; - auto send_goal_ops = rclcpp_action::Client::SendGoalOptions(); - -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - send_goal_ops.goal_response_callback = - [&goal_response_received] - (std::shared_future goal_future) - { - if (goal_future.get()) { - goal_response_received = true; - } - }; -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else -# pragma warning(pop) -#endif - - { - ActionGoal bad_goal; - bad_goal.order = -1; - auto future_goal_handle = action_client->async_send_goal(bad_goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); - auto goal_handle = future_goal_handle.get(); - EXPECT_FALSE(goal_response_received); - EXPECT_EQ(nullptr, goal_handle); - } - - { - ActionGoal goal; - goal.order = 4; - auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); - auto goal_handle = future_goal_handle.get(); - EXPECT_TRUE(goal_response_received); - EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); - EXPECT_FALSE(goal_handle->is_feedback_aware()); - EXPECT_FALSE(goal_handle->is_result_aware()); - auto future_result = action_client->async_get_result(goal_handle); - EXPECT_TRUE(goal_handle->is_result_aware()); - dual_spin_until_future_complete(future_result); - auto wrapped_result = future_result.get(); - ASSERT_EQ(5u, wrapped_result.result->sequence.size()); - EXPECT_EQ(3, wrapped_result.result->sequence.back()); - } -} - TEST_F(TestClientAgainstServer, async_send_goal_with_feedback_callback_wait_for_result) { auto action_client = rclcpp_action::create_client(client_node, action_name); diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index b091ea9c00..6048d0d691 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -333,22 +333,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override = false); - /// Declare a parameter - [[deprecated( - "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \ - "If you want to declare a parameter that won't change type without a default value use:\n" \ - "`node->declare_parameter(name)`, where e.g. ParameterT=int64_t.\n\n" \ - "If you want to declare a parameter that can dynamically change type use:\n" \ - "```\n" \ - "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \ - "descriptor.dynamic_typing = true;\n" \ - "node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \ - "```" - )]] - RCLCPP_LIFECYCLE_PUBLIC - const rclcpp::ParameterValue & - declare_parameter(const std::string & name); - /// Declare and initialize a parameter with a type. /** * \sa rclcpp::Node::declare_parameter diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index c012e50804..06378b594b 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -182,24 +182,6 @@ LifecycleNode::declare_parameter( name, default_value, parameter_descriptor, ignore_override); } -const rclcpp::ParameterValue & -LifecycleNode::declare_parameter(const std::string & name) -{ -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - return this->node_parameters_->declare_parameter(name); -#ifndef _WIN32 -# pragma GCC diagnostic pop -#else -# pragma warning(pop) -#endif -} - const rclcpp::ParameterValue & LifecycleNode::declare_parameter( const std::string & name,