Skip to content

Commit

Permalink
remove things that were deprecated during galactic (#1913)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <[email protected]>
  • Loading branch information
wjwwood authored Apr 8, 2022
1 parent 85a7046 commit 6815022
Show file tree
Hide file tree
Showing 14 changed files with 4 additions and 334 deletions.
6 changes: 0 additions & 6 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<AllocatorT> allocator) // NOLINT[runtime/explicit]
: AnySubscriptionCallback(*NotNull<AllocatorT>(allocator.get(), "invalid allocator").pointer)
{}

AnySubscriptionCallback(const AnySubscriptionCallback &) = default;

/// Generic function for setting the callback.
Expand Down
7 changes: 0 additions & 7 deletions rclcpp/include/rclcpp/duration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
16 changes: 0 additions & 16 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -395,22 +395,6 @@ class Node : public std::enable_shared_from_this<Node>
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<ParameterT>(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.
Expand Down
19 changes: 0 additions & 19 deletions rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand All @@ -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
Expand Down
5 changes: 0 additions & 5 deletions rclcpp/src/rclcpp/duration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
18 changes: 0 additions & 18 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
8 changes: 0 additions & 8 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
29 changes: 0 additions & 29 deletions rclcpp/test/rclcpp/test_any_subscription_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<test_msgs::msg::Empty> 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<test_msgs::msg::Empty> asc1;
Expand Down
16 changes: 0 additions & 16 deletions rclcpp/test/rclcpp/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
}
102 changes: 4 additions & 98 deletions rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -342,107 +342,13 @@ class Client : public ClientBase
using Feedback = typename ActionT::Feedback;
using GoalHandle = ClientGoalHandle<ActionT>;
using WrappedResult = typename GoalHandle::WrappedResult;
using GoalResponseCallback = std::function<void (typename GoalHandle::SharedPtr)>;
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<void (typename CancelResponse::SharedPtr)>;

/// Compatibility wrapper for `goal_response_callback`.
class GoalResponseCallback
{
public:
using NewSignature = std::function<void (typename GoalHandle::SharedPtr)>;
using OldSignature = std::function<void (std::shared_future<typename GoalHandle::SharedPtr>)>;

GoalResponseCallback() = default;

GoalResponseCallback(std::nullptr_t) {} // NOLINT, intentionally implicit.

// implicit constructor
[[deprecated(
"Use new goal response callback signature "
"`std::function<void (Client<ActionT>::GoalHandle::SharedPtr)>` "
"instead of the old "
"`std::function<void (std::shared_future<Client<ActionT>::GoalHandle::SharedPtr>)>`.\n"
"e.g.:\n"
"```cpp\n"
"Client<ActionT>::SendGoalOptions options;\n"
"options.goal_response_callback = [](Client<ActionT>::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<Client<ActionT>::GoalHandle::SharedPtr> goal_handle_shared_future)`"
" is deprecated.")]]
void
operator()(std::shared_future<typename GoalHandle::SharedPtr> 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<typename GoalHandle::SharedPtr> 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`.
Expand Down Expand Up @@ -524,14 +430,14 @@ class Client : public ClientBase
goal_request->goal = goal;
this->send_goal_request(
std::static_pointer_cast<void>(goal_request),
[this, goal_request, options, promise, future](std::shared_ptr<void> response) mutable
[this, goal_request, options, promise](std::shared_ptr<void> response) mutable
{
using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
auto goal_response = std::static_pointer_cast<GoalResponse>(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;
}
Expand All @@ -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) {
Expand Down
Loading

0 comments on commit 6815022

Please sign in to comment.