Skip to content

Commit

Permalink
updates since changes to message_info in rclcpp (#423)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <[email protected]>
  • Loading branch information
wjwwood authored Apr 14, 2020
1 parent 4ccd6e3 commit cd1b2d1
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 10 deletions.
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 =
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_intra_process.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<unsigned int>(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;
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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](
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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](
Expand Down

0 comments on commit cd1b2d1

Please sign in to comment.