Skip to content

Commit

Permalink
Change up the formatting in the test_rclcpp tests. (#537)
Browse files Browse the repository at this point in the history
Newer uncrustify changes the indentation around lambdas.
Avoid that here by making sure the lambdas are all on
either one or two lines, which should make this work
for both current and newer uncrustify.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette authored Feb 26, 2024
1 parent 2144c02 commit 3f6fd66
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,7 @@ TEST_F(test_avoid_ros_namespace_conventions_qos, pub_sub_works)
// code to create the callback and subscription
int counter = 0;
auto callback =
[&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg,
const rclcpp::MessageInfo & info) -> void
[&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, const rclcpp::MessageInfo & info)
{
++counter;
printf(" callback() %d with message data %u\n", counter, msg->data);
Expand Down
24 changes: 12 additions & 12 deletions test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,9 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
std::vector<rclcpp::Subscription<test_rclcpp::msg::UInt32>::SharedPtr> subscriptions;
std::atomic_int counter(0);

using MsgType = test_rclcpp::msg::UInt32;
auto callback =
[&counter, &intra_process](test_rclcpp::msg::UInt32::ConstSharedPtr msg,
const rclcpp::MessageInfo & info) -> void
[&counter, &intra_process](MsgType::ConstSharedPtr msg, const rclcpp::MessageInfo & info)
{
counter.fetch_add(1);
printf("callback() %d with message data %u\n", counter.load(), msg->data);
Expand All @@ -79,15 +79,15 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
rclcpp::SubscriptionOptions subscription_options;
subscription_options.callback_group = callback_group;
for (uint32_t i = 0; i < num_messages; ++i) {
auto sub = node->create_subscription<test_rclcpp::msg::UInt32>(
auto sub = node->create_subscription<MsgType>(
node_topic_name, 5 * num_messages, callback, subscription_options);
subscriptions.push_back(sub);
}
ASSERT_TRUE(static_cast<size_t>(std::numeric_limits<int>::max()) > subscriptions.size());
int subscriptions_size = static_cast<int>(subscriptions.size());

executor.add_node(node);
test_rclcpp::msg::UInt32 msg;
MsgType msg;
msg.data = 0;

// wait a moment for everything to initialize
Expand Down Expand Up @@ -169,8 +169,9 @@ TEST_F(test_multithreaded, multi_consumer_clients)
rclcpp::executors::MultiThreadedExecutor executor;

std::atomic_int counter(0);
auto callback = [&counter](const std::shared_ptr<test_rclcpp::srv::AddTwoInts::Request> request,
std::shared_ptr<test_rclcpp::srv::AddTwoInts::Response> response)
using SrvType = test_rclcpp::srv::AddTwoInts;
auto callback =
[&counter](const SrvType::Request::SharedPtr request, SrvType::Response::SharedPtr response)
{
printf("Called service callback: %d\n", counter.load());
++counter;
Expand All @@ -185,16 +186,15 @@ TEST_F(test_multithreaded, multi_consumer_clients)
"multi_consumer_clients", callback, qos_profile, callback_group);

using ClientRequestPair = std::pair<
rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedPtr,
test_rclcpp::srv::AddTwoInts::Request::SharedPtr>;
using SharedFuture = rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;

rclcpp::Client<SrvType>::SharedPtr,
SrvType::Request::SharedPtr>;
using SharedFuture = rclcpp::Client<SrvType>::SharedFuture;

std::vector<ClientRequestPair> client_request_pairs;
for (uint32_t i = 0; i < 2 * std::min<size_t>(executor.get_number_of_threads(), 16); ++i) {
auto client = node->create_client<test_rclcpp::srv::AddTwoInts>(
auto client = node->create_client<SrvType>(
"multi_consumer_clients", qos_profile, callback_group);
auto request = std::make_shared<test_rclcpp::srv::AddTwoInts::Request>();
auto request = std::make_shared<SrvType::Request>();
request->a = i;
request->b = i + 1;
client_request_pairs.push_back(ClientRequestPair(client, request));
Expand Down
3 changes: 1 addition & 2 deletions test_rclcpp/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,7 @@ TEST_F(test_publisher, publish_with_const_reference)
// code to create the callback and subscription
int counter = 0;
auto callback =
[&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg,
const rclcpp::MessageInfo & info) -> void
[&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, const rclcpp::MessageInfo & info)
{
++counter;
printf(" callback() %d with message data %u\n", counter, msg->data);
Expand Down
3 changes: 1 addition & 2 deletions test_rclcpp/test/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,8 +290,7 @@ TEST_F(test_subscription, subscription_shared_ptr_const_with_info)
// create the callback and subscription
int counter = 0;
auto callback =
[&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg,
const rclcpp::MessageInfo & info) -> void
[&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, const rclcpp::MessageInfo & info)
{
++counter;
printf(" callback() %d with message data %u\n", counter, msg->data);
Expand Down

0 comments on commit 3f6fd66

Please sign in to comment.