Skip to content

Commit

Permalink
Fix deprecated sub callbacks in test_rclcpp
Browse files Browse the repository at this point in the history
Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>
  • Loading branch information
Abrar Rahman Protyasha committed Aug 20, 2021
1 parent b21f960 commit 1f68dea
Show file tree
Hide file tree
Showing 5 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_intra_process.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ TEST_F(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nomina
int counter = 0;
auto callback =
[&counter](
const test_rclcpp::msg::UInt32::SharedPtr msg,
const test_rclcpp::msg::UInt32::ConstSharedPtr msg,
const rclcpp::MessageInfo & message_info
) -> void
{
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,7 @@ static inline void multi_access_publisher(bool intra_process)
// callback groups?

std::atomic_uint subscription_counter(0);
auto sub_callback = [&subscription_counter](const test_rclcpp::msg::UInt32::SharedPtr msg)
auto sub_callback = [&subscription_counter](const test_rclcpp::msg::UInt32::ConstSharedPtr msg)
{
++subscription_counter;
printf("Subscription callback %u\n", subscription_counter.load());
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_repeated_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ TEST_F(
auto node = rclcpp::Node::make_shared("test_repeated_publisher_subscriber");

auto callback =
[](const test_rclcpp::msg::UInt32::SharedPtr) -> void
[](const test_rclcpp::msg::UInt32::ConstSharedPtr) -> void
{
};

Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinni
std::shared_future<void> sub_called_future(sub_called.get_future());
auto fail_after_timeout = 5s;
auto callback =
[&counter, &sub_called](const test_rclcpp::msg::UInt32::SharedPtr msg) -> void
[&counter, &sub_called](const test_rclcpp::msg::UInt32::ConstSharedPtr msg) -> void
{
++counter;
printf(" callback() %d with message data %u\n", counter, msg->data);
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_timeout_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

void callback(const test_rclcpp::msg::UInt32::SharedPtr /*msg*/)
void callback(const test_rclcpp::msg::UInt32::ConstSharedPtr /*msg*/)
{
throw std::runtime_error("The subscriber received a message but there should be no publisher!");
}
Expand Down

0 comments on commit 1f68dea

Please sign in to comment.