From 562776ac748128c148aa4c4e25e808ba35cdc2dc Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 14 Apr 2020 07:58:53 -0700 Subject: [PATCH] updates since changes to message_info in rclcpp Signed-off-by: William Woodall --- test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp | 4 ++-- test_rclcpp/test/test_intra_process.cpp | 4 ++-- test_rclcpp/test/test_multithreaded.cpp | 4 ++-- test_rclcpp/test/test_publisher.cpp | 4 ++-- test_rclcpp/test/test_subscription.cpp | 4 ++-- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp index 740a69df..f9eea2fa 100644 --- a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp +++ b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp @@ -44,11 +44,11 @@ TEST( int counter = 0; auto callback = [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rmw_message_info_t & info) -> void + const rclcpp::MessageInfo & info) -> void { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data); - ASSERT_FALSE(info.from_intra_process); + ASSERT_FALSE(info.get_rmw_message_info().from_intra_process); }; auto qos = rclcpp::QoS(rclcpp::KeepLast(10)).avoid_ros_namespace_conventions(true); auto create_subscription_func = diff --git a/test_rclcpp/test/test_intra_process.cpp b/test_rclcpp/test/test_intra_process.cpp index 8c8a7e59..45d08b88 100644 --- a/test_rclcpp/test/test_intra_process.cpp +++ b/test_rclcpp/test/test_intra_process.cpp @@ -47,14 +47,14 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_ auto callback = [&counter]( const test_rclcpp::msg::UInt32::SharedPtr msg, - const rmw_message_info_t & message_info + const rclcpp::MessageInfo & message_info ) -> void { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data); ASSERT_GE(counter, 0); ASSERT_EQ(static_cast(counter), msg->data); - ASSERT_TRUE(message_info.from_intra_process); + ASSERT_TRUE(message_info.get_rmw_message_info().from_intra_process); }; test_rclcpp::msg::UInt32 msg; diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index 8b1c615d..39552ece 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -60,11 +60,11 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) auto callback = [&counter, &intra_process](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rmw_message_info_t & info) -> void + const rclcpp::MessageInfo & info) -> void { counter.fetch_add(1); printf("callback() %d with message data %u\n", counter.load(), msg->data); - ASSERT_EQ(intra_process, info.from_intra_process); + ASSERT_EQ(intra_process, info.get_rmw_message_info().from_intra_process); }; // Try to saturate the MultithreadedExecutor's thread pool with subscriptions diff --git a/test_rclcpp/test/test_publisher.cpp b/test_rclcpp/test/test_publisher.cpp index 8bbe9d70..0e247b89 100644 --- a/test_rclcpp/test/test_publisher.cpp +++ b/test_rclcpp/test/test_publisher.cpp @@ -41,11 +41,11 @@ TEST(CLASSNAME(test_publisher, RMW_IMPLEMENTATION), publish_with_const_reference int counter = 0; auto callback = [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rmw_message_info_t & info) -> void + const rclcpp::MessageInfo & info) -> void { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data); - ASSERT_FALSE(info.from_intra_process); + ASSERT_FALSE(info.get_rmw_message_info().from_intra_process); }; auto create_subscription_func = [&callback]( diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index 246d3aa3..3316a00a 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -291,11 +291,11 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_c int counter = 0; auto callback = [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rmw_message_info_t & info) -> void + const rclcpp::MessageInfo & info) -> void { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data); - ASSERT_FALSE(info.from_intra_process); + ASSERT_FALSE(info.get_rmw_message_info().from_intra_process); }; auto create_subscription_func = [&callback](