Skip to content

Commit

Permalink
Remove the set_deprecated signatures in any_subscription_callback. (#…
Browse files Browse the repository at this point in the history
…2431)

These have been deprecated since April 2021, so it is safe
to remove them now.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette authored Feb 23, 2024
1 parent 1981e1f commit e10728c
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 50 deletions.
49 changes: 1 addition & 48 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@
#include "rclcpp/serialized_message.hpp"
#include "rclcpp/type_adapter.hpp"


namespace rclcpp
{

Expand Down Expand Up @@ -394,58 +393,12 @@ class AnySubscriptionCallback
// converted to one another, e.g. shared_ptr and unique_ptr.
using scbth = detail::SubscriptionCallbackTypeHelper<MessageT, CallbackT>;

// Determine if the given CallbackT is a deprecated signature or not.
constexpr auto is_deprecated =
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<MessageT>)>
>::value
||
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<MessageT>, const rclcpp::MessageInfo &)>
>::value;

// Use the discovered type to force the type of callback when assigning
// into the variant.
if constexpr (is_deprecated) {
// If deprecated, call sub-routine that is deprecated.
set_deprecated(static_cast<typename scbth::callback_type>(callback));
} else {
// Otherwise just assign it.
callback_variant_ = static_cast<typename scbth::callback_type>(callback);
}
callback_variant_ = static_cast<typename scbth::callback_type>(callback);

// Return copy of self for easier testing, normally will be compiled out.
return *this;
}

/// Function for shared_ptr to non-const MessageT, which is deprecated.
template<typename SetT>
#if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS)
// suppress deprecation warnings in `test_any_subscription_callback.cpp`
[[deprecated("use 'void(std::shared_ptr<const MessageT>)' instead")]]
#endif
void
set_deprecated(std::function<void(std::shared_ptr<SetT>)> callback)
{
callback_variant_ = callback;
}

/// Function for shared_ptr to non-const MessageT with MessageInfo, which is deprecated.
template<typename SetT>
#if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS)
// suppress deprecation warnings in `test_any_subscription_callback.cpp`
[[deprecated(
"use 'void(std::shared_ptr<const MessageT>, const rclcpp::MessageInfo &)' instead"
)]]
#endif
void
set_deprecated(std::function<void(std::shared_ptr<SetT>, const rclcpp::MessageInfo &)> callback)
{
callback_variant_ = callback;
}

std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
create_ros_unique_ptr_from_ros_shared_ptr_message(
const std::shared_ptr<const ROSMessageType> & message)
Expand Down
2 changes: 0 additions & 2 deletions rclcpp/test/rclcpp/test_any_subscription_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@
#include <string>
#include <utility>

// TODO(aprotyas): Figure out better way to suppress deprecation warnings.
#define RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS 1
#include "rclcpp/any_subscription_callback.hpp"
#include "test_msgs/msg/empty.hpp"
#include "test_msgs/msg/empty.h"
Expand Down

0 comments on commit e10728c

Please sign in to comment.