Skip to content

Commit

Permalink
Various cleanups to deal with uncrustify 0.78. (#2439)
Browse files Browse the repository at this point in the history
These should also work with uncrustify 0.72.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette authored Feb 29, 2024
1 parent 64f9aa1 commit 726f203
Show file tree
Hide file tree
Showing 10 changed files with 95 additions and 102 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,7 @@ init_tuple(NodeT & n)
* something like that, then you'll need to create your own specialization of
* the NodeInterfacesSupports struct without this macro.
*/
// *INDENT-OFF*
#define RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(NodeInterfaceType, NodeInterfaceName) \
namespace rclcpp::node_interfaces::detail { \
template<typename StorageClassT, typename ... RemainingInterfaceTs> \
Expand All @@ -189,7 +190,7 @@ init_tuple(NodeT & n)
/* Perfect forwarding constructor to get arguments down to StorageClassT (eventually). */ \
template<typename ... ArgsT> \
explicit NodeInterfacesSupports(ArgsT && ... args) \
: NodeInterfacesSupports<StorageClassT, RemainingInterfaceTs ...>( \
: NodeInterfacesSupports<StorageClassT, RemainingInterfaceTs ...>( \
std::forward<ArgsT>(args) ...) \
{} \
\
Expand All @@ -200,6 +201,7 @@ init_tuple(NodeT & n)
} \
}; \
} // namespace rclcpp::node_interfaces::detail
// *INDENT-ON*

} // namespace detail
} // namespace node_interfaces
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,7 @@ class Subscription : public SubscriptionBase
* of the following conditions are true: qos_profile.history == RMW_QOS_POLICY_HISTORY_KEEP_ALL,
* qos_profile.depth == 0 or qos_profile.durability != RMW_QOS_POLICY_DURABILITY_VOLATILE).
*/
// *INDENT-OFF*
Subscription(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
const rosidl_message_type_support_t & type_support_handle,
Expand All @@ -148,6 +149,7 @@ class Subscription : public SubscriptionBase
any_callback_(callback),
options_(options),
message_memory_strategy_(message_memory_strategy)
// *INDENT-ON*
{
// Setup intra process publishing if requested.
if (rclcpp::detail::resolve_use_intra_process(options_, *node_base)) {
Expand Down
5 changes: 3 additions & 2 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,8 +95,9 @@ Executor::~Executor()
}
// Disassociate all nodes.
std::for_each(
weak_nodes_.begin(), weak_nodes_.end(), []
(rclcpp::node_interfaces::NodeBaseInterface::WeakPtr weak_node_ptr) {
weak_nodes_.begin(), weak_nodes_.end(),
[](rclcpp::node_interfaces::NodeBaseInterface::WeakPtr weak_node_ptr)
{
auto shared_node_ptr = weak_node_ptr.lock();
if (shared_node_ptr) {
std::atomic_bool & has_executor = shared_node_ptr->get_associated_with_executor_atomic();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -409,8 +409,10 @@ StaticExecutorEntitiesCollector::remove_node(
std::for_each(
weak_groups_to_nodes_associated_with_executor_.begin(),
weak_groups_to_nodes_associated_with_executor_.end(),
[&found_group_ptrs, node_ptr](std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> key_value_pair) {
[&found_group_ptrs, node_ptr](
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> key_value_pair)
{
auto & weak_node_ptr = key_value_pair.second;
auto shared_node_ptr = weak_node_ptr.lock();
auto group_ptr = key_value_pair.first.lock();
Expand All @@ -419,8 +421,9 @@ StaticExecutorEntitiesCollector::remove_node(
}
});
std::for_each(
found_group_ptrs.begin(), found_group_ptrs.end(), [this]
(rclcpp::CallbackGroup::SharedPtr group_ptr) {
found_group_ptrs.begin(), found_group_ptrs.end(),
[this](rclcpp::CallbackGroup::SharedPtr group_ptr)
{
this->remove_callback_group_from_map(
group_ptr,
weak_groups_to_nodes_associated_with_executor_);
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,9 +200,9 @@ class TestAllocatorMemoryStrategy : public ::testing::Test

std::shared_ptr<rclcpp::Node> create_node_with_service(const std::string & name)
{
auto service_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service_callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto node_with_service = create_node_with_disabled_callback_groups(name);

auto callback_group =
Expand Down Expand Up @@ -949,9 +949,9 @@ TEST_F(TestAllocatorMemoryStrategy, get_next_service_out_of_scope) {
node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);

auto service_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service_callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service = node->create_service<test_msgs::srv::Empty>(
"service", std::move(service_callback), rclcpp::ServicesQoS(), callback_group);

Expand Down
29 changes: 16 additions & 13 deletions rclcpp/test/rclcpp/test_any_service_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,10 @@ TEST_F(TestAnyServiceCallback, no_set_and_dispatch_throw) {

TEST_F(TestAnyServiceCallback, set_and_dispatch_no_header) {
int callback_calls = 0;
auto callback = [&callback_calls](const std::shared_ptr<test_msgs::srv::Empty::Request>,
std::shared_ptr<test_msgs::srv::Empty::Response>) {
auto callback = [&callback_calls](
const std::shared_ptr<test_msgs::srv::Empty::Request>,
std::shared_ptr<test_msgs::srv::Empty::Response>)
{
callback_calls++;
};

Expand All @@ -65,10 +67,11 @@ TEST_F(TestAnyServiceCallback, set_and_dispatch_no_header) {

TEST_F(TestAnyServiceCallback, set_and_dispatch_header) {
int callback_with_header_calls = 0;
auto callback_with_header =
[&callback_with_header_calls](const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<test_msgs::srv::Empty::Request>,
std::shared_ptr<test_msgs::srv::Empty::Response>) {
auto callback_with_header = [&callback_with_header_calls](
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<test_msgs::srv::Empty::Request>,
std::shared_ptr<test_msgs::srv::Empty::Response>)
{
callback_with_header_calls++;
};

Expand All @@ -80,9 +83,9 @@ TEST_F(TestAnyServiceCallback, set_and_dispatch_header) {

TEST_F(TestAnyServiceCallback, set_and_dispatch_defered) {
int callback_with_header_calls = 0;
auto callback_with_header =
[&callback_with_header_calls](const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<test_msgs::srv::Empty::Request>) {
auto callback_with_header = [&callback_with_header_calls](
const std::shared_ptr<rmw_request_id_t>, const std::shared_ptr<test_msgs::srv::Empty::Request>)
{
callback_with_header_calls++;
};

Expand All @@ -94,10 +97,10 @@ TEST_F(TestAnyServiceCallback, set_and_dispatch_defered) {

TEST_F(TestAnyServiceCallback, set_and_dispatch_defered_with_service_handle) {
int callback_with_header_calls = 0;
auto callback_with_header =
[&callback_with_header_calls](std::shared_ptr<rclcpp::Service<test_msgs::srv::Empty>>,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<test_msgs::srv::Empty::Request>)
auto callback_with_header = [&callback_with_header_calls](
std::shared_ptr<rclcpp::Service<test_msgs::srv::Empty>>,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<test_msgs::srv::Empty::Request>)
{
callback_with_header_calls++;
};
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/test/rclcpp/test_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,9 +143,9 @@ TEST_F(TestMemoryStrategy, get_service_by_handle) {
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto service_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service_callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
const rclcpp::QoS qos(10);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
Expand Down Expand Up @@ -389,9 +389,9 @@ TEST_F(TestMemoryStrategy, get_group_by_service) {
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto service_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service_callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
const rclcpp::QoS qos(10);

service = node->create_service<test_msgs::srv::Empty>(
Expand Down
78 changes: 35 additions & 43 deletions rclcpp/test/rclcpp/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,12 +88,11 @@ class TestServiceSub : public ::testing::Test
Testing service construction and destruction.
*/
TEST_F(TestService, construction_and_destruction) {
using rcl_interfaces::srv::ListParameters;
auto callback =
[](const ListParameters::Request::SharedPtr, ListParameters::Response::SharedPtr) {
};
auto callback = [](
const rcl_interfaces::srv::ListParameters::Request::SharedPtr,
rcl_interfaces::srv::ListParameters::Response::SharedPtr) {};
{
auto service = node->create_service<ListParameters>("service", callback);
auto service = node->create_service<rcl_interfaces::srv::ListParameters>("service", callback);
EXPECT_NE(nullptr, service->get_service_handle());
const rclcpp::ServiceBase * const_service_base = service.get();
EXPECT_NE(nullptr, const_service_base->get_service_handle());
Expand All @@ -102,7 +101,8 @@ TEST_F(TestService, construction_and_destruction) {
{
ASSERT_THROW(
{
auto service = node->create_service<ListParameters>("invalid_service?", callback);
auto service = node->create_service<rcl_interfaces::srv::ListParameters>(
"invalid_service?", callback);
}, rclcpp::exceptions::InvalidServiceNameError);
}
}
Expand All @@ -111,27 +111,27 @@ TEST_F(TestService, construction_and_destruction) {
Testing service construction and destruction for subnodes.
*/
TEST_F(TestServiceSub, construction_and_destruction) {
using rcl_interfaces::srv::ListParameters;
auto callback =
[](const ListParameters::Request::SharedPtr, ListParameters::Response::SharedPtr) {
};
auto callback = [](
const rcl_interfaces::srv::ListParameters::Request::SharedPtr,
rcl_interfaces::srv::ListParameters::Response::SharedPtr) {};
{
auto service = subnode->create_service<ListParameters>("service", callback);
auto service = subnode->create_service<rcl_interfaces::srv::ListParameters>(
"service", callback);
EXPECT_STREQ(service->get_service_name(), "/ns/sub_ns/service");
}

{
ASSERT_THROW(
{
auto service = node->create_service<ListParameters>("invalid_service?", callback);
auto service = node->create_service<rcl_interfaces::srv::ListParameters>(
"invalid_service?", callback);
}, rclcpp::exceptions::InvalidServiceNameError);
}
}

TEST_F(TestService, construction_and_destruction_rcl_errors) {
auto callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {};

{
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_service_init, RCL_RET_ERROR);
Expand All @@ -149,11 +149,10 @@ TEST_F(TestService, construction_and_destruction_rcl_errors) {

/* Testing basic getters */
TEST_F(TestService, basic_public_getters) {
using rcl_interfaces::srv::ListParameters;
auto callback =
[](const ListParameters::Request::SharedPtr, ListParameters::Response::SharedPtr) {
};
auto service = node->create_service<ListParameters>("service", callback);
auto callback = [](
const rcl_interfaces::srv::ListParameters::Request::SharedPtr,
rcl_interfaces::srv::ListParameters::Response::SharedPtr) {};
auto service = node->create_service<rcl_interfaces::srv::ListParameters>("service", callback);
EXPECT_STREQ(service->get_service_name(), "/ns/service");
std::shared_ptr<rcl_service_t> service_handle = service->get_service_handle();
EXPECT_NE(nullptr, service_handle);
Expand Down Expand Up @@ -189,9 +188,8 @@ TEST_F(TestService, basic_public_getters) {
}

TEST_F(TestService, take_request) {
auto callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {};
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);
{
auto request_id = server->create_request_header();
Expand All @@ -217,9 +215,8 @@ TEST_F(TestService, take_request) {
}

TEST_F(TestService, send_response) {
auto callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {};
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);

{
Expand All @@ -243,9 +240,9 @@ TEST_F(TestService, send_response) {
Testing on_new_request callbacks.
*/
TEST_F(TestService, on_new_request_callback) {
auto server_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {FAIL();};
auto server_callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {FAIL();};
rclcpp::ServicesQoS service_qos;
service_qos.keep_last(3);
auto server = node->create_service<test_msgs::srv::Empty>(
Expand Down Expand Up @@ -315,9 +312,8 @@ TEST_F(TestService, on_new_request_callback) {
TEST_F(TestService, rcl_service_response_publisher_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_service_response_publisher_get_actual_qos, nullptr);
auto callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {};
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);
RCLCPP_EXPECT_THROW_EQ(
server->get_response_publisher_actual_qos(),
Expand All @@ -327,9 +323,8 @@ TEST_F(TestService, rcl_service_response_publisher_get_actual_qos_error) {
TEST_F(TestService, rcl_service_request_subscription_get_actual_qos_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_service_request_subscription_get_actual_qos, nullptr);
auto callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {};
auto server = node->create_service<test_msgs::srv::Empty>("service", callback);
RCLCPP_EXPECT_THROW_EQ(
server->get_request_subscription_actual_qos(),
Expand All @@ -345,11 +340,10 @@ TEST_F(TestService, server_qos) {
qos_profile.lifespan(duration);
qos_profile.liveliness_lease_duration(duration);

auto callback = [](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {};

auto server = node->create_service<test_msgs::srv::Empty>(
"service", callback, qos_profile);
auto server = node->create_service<test_msgs::srv::Empty>("service", callback, qos_profile);
auto rs_qos = server->get_request_subscription_actual_qos();
auto rp_qos = server->get_response_publisher_actual_qos();

Expand All @@ -360,8 +354,6 @@ TEST_F(TestService, server_qos) {
}

TEST_F(TestService, server_qos_depth) {
using namespace std::literals::chrono_literals;

uint64_t server_cb_count_ = 0;
auto server_callback = [&](
const test_msgs::srv::Empty::Request::SharedPtr,
Expand All @@ -380,8 +372,8 @@ TEST_F(TestService, server_qos_depth) {
::testing::AssertionResult request_result = ::testing::AssertionSuccess();
auto request = std::make_shared<test_msgs::srv::Empty::Request>();

using SharedFuture = rclcpp::Client<test_msgs::srv::Empty>::SharedFuture;
auto client_callback = [&request_result](SharedFuture future_response) {
auto client_callback = [&request_result](
rclcpp::Client<test_msgs::srv::Empty>::SharedFuture future_response) {
if (nullptr == future_response.get()) {
request_result = ::testing::AssertionFailure() << "Future response was null";
}
Expand Down
22 changes: 8 additions & 14 deletions rclcpp/test/rclcpp/test_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,20 +285,14 @@ TEST_P(TestTimer, test_failures_with_exceptions)
std::shared_ptr<rclcpp::TimerBase> timer_to_test_destructor;
// Test destructor failure, just logs a msg
auto mock = mocking_utils::inject_on_return("lib:rclcpp", rcl_timer_fini, RCL_RET_ERROR);
EXPECT_NO_THROW(
{
switch (timer_type) {
case TimerType::WALL_TIMER:
timer_to_test_destructor =
test_node->create_wall_timer(std::chrono::milliseconds(0), [](void) {});
break;
case TimerType::GENERIC_TIMER:
timer_to_test_destructor =
test_node->create_timer(std::chrono::milliseconds(0), [](void) {});
break;
}
timer_to_test_destructor.reset();
});
if (timer_type == TimerType::WALL_TIMER) {
timer_to_test_destructor =
test_node->create_wall_timer(std::chrono::milliseconds(0), [](void) {});
} else {
timer_to_test_destructor =
test_node->create_timer(std::chrono::milliseconds(0), [](void) {});
}
timer_to_test_destructor.reset();
}
{
auto mock = mocking_utils::patch_and_return(
Expand Down
Loading

0 comments on commit 726f203

Please sign in to comment.