Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
63 changes: 62 additions & 1 deletion rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -407,12 +407,73 @@ class AnySubscriptionCallback
// converted to one another, e.g. shared_ptr and unique_ptr.
using scbth = detail::SubscriptionCallbackTypeHelper<MessageT, CallbackT>;

callback_variant_ = static_cast<typename scbth::callback_type>(callback);
// 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<SubscribedType>)>
>::value ||
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<SubscribedType>, const rclcpp::MessageInfo &)>
>::value ||
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<ROSMessageType>)>
>::value ||
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<ROSMessageType>, const rclcpp::MessageInfo &)>
>::value ||
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)>
>::value ||
rclcpp::function_traits::same_arguments<
typename scbth::callback_type,
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>, 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);
}

// 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;
}

/// Disable the callback from being called during dispatch.
void disable()
{
Expand Down
5 changes: 3 additions & 2 deletions rclcpp/test/rclcpp/test_any_subscription_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <string>
#include <utility>

#define RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS 1
#include "rclcpp/any_subscription_callback.hpp"
#include "test_msgs/msg/empty.hpp"

Expand Down Expand Up @@ -178,7 +179,7 @@ TEST_F(TestAnySubscriptionCallback, is_serialized_message_callback) {
}
{
rclcpp::AnySubscriptionCallback<test_msgs::msg::Empty> asc;
asc.set([](std::shared_ptr<rclcpp::SerializedMessage>) {});
asc.set([](std::shared_ptr<const rclcpp::SerializedMessage>) {});
EXPECT_TRUE(asc.is_serialized_message_callback());
EXPECT_NO_THROW(
asc.dispatch(
Expand All @@ -187,7 +188,7 @@ TEST_F(TestAnySubscriptionCallback, is_serialized_message_callback) {
}
{
rclcpp::AnySubscriptionCallback<test_msgs::msg::Empty> asc;
asc.set([](std::shared_ptr<rclcpp::SerializedMessage>, const rclcpp::MessageInfo &) {});
asc.set([](std::shared_ptr<const rclcpp::SerializedMessage>, const rclcpp::MessageInfo &) {});
EXPECT_TRUE(asc.is_serialized_message_callback());
EXPECT_NO_THROW(
asc.dispatch(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<std::string> msg) -> void {
std::shared_ptr<const std::string> msg) -> void {
is_received = true;
EXPECT_STREQ(message_data.c_str(), (*msg).c_str());
};
Expand All @@ -230,7 +230,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<std::string> msg,
std::shared_ptr<const std::string> msg,
const rclcpp::MessageInfo & message_info) -> void {
is_received = true;
EXPECT_STREQ(message_data.c_str(), (*msg).c_str());
Expand Down Expand Up @@ -422,7 +422,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<std::string> msg) -> void {
std::shared_ptr<const std::string> msg) -> void {
is_received = true;
EXPECT_STREQ(message_data.c_str(), (*msg).c_str());
};
Expand All @@ -440,7 +440,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<std::string> msg,
std::shared_ptr<const std::string> msg,
const rclcpp::MessageInfo & message_info) -> void {
is_received = true;
EXPECT_STREQ(message_data.c_str(), (*msg).c_str());
Expand Down Expand Up @@ -637,7 +637,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<double> msg) -> void {
std::shared_ptr<const double> msg) -> void {
is_received = true;
ASSERT_EQ(message_data, *msg);
};
Expand All @@ -656,7 +656,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<double> msg,
std::shared_ptr<const double> msg,
const rclcpp::MessageInfo & message_info) -> void {
is_received = true;
ASSERT_EQ(message_data, *msg);
Expand Down Expand Up @@ -862,7 +862,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<double> msg) -> void {
std::shared_ptr<const double> msg) -> void {
is_received = true;
ASSERT_EQ(message_data, *msg);
};
Expand All @@ -882,7 +882,7 @@ TEST_F(
bool is_received = false;
auto callback =
[message_data, &is_received](
std::shared_ptr<double> msg,
std::shared_ptr<const double> msg,
const rclcpp::MessageInfo & message_info) -> void {
is_received = true;
ASSERT_EQ(message_data, *msg);
Expand Down