Skip to content

Commit

Permalink
Fix deprecated subscriber callback warnings (#483)
Browse files Browse the repository at this point in the history
* Fixing deprecated subscriber callback warnings

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Fix deprecated sub callbacks in `test_rclcpp`

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Fix deprecated sub callbacks in `test_security`

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Fix line formatting in `test_publisher_subscriber`

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>
Co-authored-by: William Woodall <william@osrfoundation.org>

* Fix line formatting in some unit tests

Signed-off-by: Abrar Rahman Protyasha <abrar@openrobotics.org>

* Address `ament_uncrustify` warnings

Signed-off-by: aprotyas <aprotyas@u.rochester.edu>

Co-authored-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
Abrar Rahman Protyasha and wjwwood authored Aug 26, 2021
1 parent 8b43c19 commit fab8e95
Show file tree
Hide file tree
Showing 11 changed files with 19 additions and 12 deletions.
4 changes: 3 additions & 1 deletion test_communication/test/test_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,9 @@ rclcpp::SubscriptionBase::SharedPtr subscribe(
received_messages.assign(expected_messages.size(), false);

auto callback =
[&expected_messages, &received_messages](const typename T::SharedPtr received_message) -> void
[&expected_messages, &received_messages](
const typename T::ConstSharedPtr received_message
) -> void
{
// find received message in vector of expected messages
auto received = received_messages.begin();
Expand Down
4 changes: 3 additions & 1 deletion test_communication/test/test_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@ rclcpp::SubscriptionBase::SharedPtr subscribe(
received_messages.assign(expected_messages.size(), false);

auto callback =
[&expected_messages, &received_messages](const typename T::SharedPtr received_message) -> void
[&expected_messages, &received_messages](
const typename T::ConstSharedPtr received_message
) -> void
{
// find received message in vector of expected messages
auto received = received_messages.begin();
Expand Down
2 changes: 1 addition & 1 deletion test_communication/test/test_subscription_valid_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ int main(int argc, char ** argv)
auto node = rclcpp::Node::make_shared("test_subscription_valid_data");

auto callback =
[](const test_communication::msg::UInt32::SharedPtr received_message) -> void
[](const test_communication::msg::UInt32::ConstSharedPtr received_message) -> void
{
printf("received message #%u\n", received_message->data);
if (received_message->data == 0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class QosTestSubscriber : public QosTestNode
void teardown() override;

private:
void listen_to_message(std_msgs::msg::String::SharedPtr);
void listen_to_message(std_msgs::msg::String::ConstSharedPtr);
void setup_start() override;
void setup_stop() override;

Expand Down
3 changes: 2 additions & 1 deletion test_quality_of_service/test/qos_test_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ QosTestSubscriber::QosTestSubscriber(
RCLCPP_INFO(this->get_logger(), "created subscriber %s %s", name.c_str(), topic.c_str());
}

void QosTestSubscriber::listen_to_message(const std_msgs::msg::String::SharedPtr received_message)
void QosTestSubscriber::listen_to_message(
const std_msgs::msg::String::ConstSharedPtr received_message)
{
RCLCPP_INFO(
this->get_logger(), "%s: subscriber heard [%s]", this->name_.c_str(),
Expand Down
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
6 changes: 4 additions & 2 deletions test_security/test/test_secure_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,9 @@ rclcpp::SubscriptionBase::SharedPtr attempt_subscribe(
received_messages.assign(expected_messages.size(), false);

auto callback =
[&expected_messages, &received_messages](const typename T::SharedPtr received_message) -> void
[&expected_messages, &received_messages](
const typename T::ConstSharedPtr received_message
) -> void
{
// find received message in vector of expected messages
auto received = received_messages.begin();
Expand Down Expand Up @@ -77,7 +79,7 @@ rclcpp::SubscriptionBase::SharedPtr attempt_subscribe(
rclcpp::executors::SingleThreadedExecutor & exec)
{
auto subscription_callback =
[&sub_callback_called, &exec](const typename T::SharedPtr) -> void
[&sub_callback_called, &exec](const typename T::ConstSharedPtr) -> void
{
printf("***SUB_CALLBACK***\n");
sub_callback_called = true;
Expand Down

0 comments on commit fab8e95

Please sign in to comment.