Skip to content

Commit a524bf0

Browse files
committed
Lint
Signed-off-by: Michael Carroll <[email protected]>
1 parent 173ffd6 commit a524bf0

File tree

4 files changed

+26
-24
lines changed

4 files changed

+26
-24
lines changed

rclcpp/include/rclcpp/executors/executor_entities_collection.hpp

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@
1515
#ifndef RCLCPP__EXECUTORS__EXECUTOR_ENTITIES_COLLECTION_HPP_
1616
#define RCLCPP__EXECUTORS__EXECUTOR_ENTITIES_COLLECTION_HPP_
1717

18-
#include "rclcpp/subscription_base.hpp"
1918
#include <deque>
2019
#include <unordered_map>
2120
#include <vector>
@@ -33,18 +32,19 @@ namespace rclcpp
3332
namespace executors
3433
{
3534

36-
template <typename EntityValueType>
37-
struct CollectionEntry {
35+
template<typename EntityValueType>
36+
struct CollectionEntry
37+
{
3838
typename EntityValueType::WeakPtr entity;
3939
rclcpp::CallbackGroup::WeakPtr callback_group;
4040
};
4141

42-
template <typename CollectionType>
42+
template<typename CollectionType>
4343
void update_entities(
4444
const CollectionType & update_from,
4545
CollectionType update_to,
46-
std::function<void (typename CollectionType::mapped_type::EntitySharedPtr) > on_added,
47-
std::function<void (typename CollectionType::mapped_type::EntitySharedPtr) > on_removed
46+
std::function<void(typename CollectionType::mapped_type::EntitySharedPtr)> on_added,
47+
std::function<void(typename CollectionType::mapped_type::EntitySharedPtr)> on_removed
4848
)
4949
{
5050
for (auto it = update_to.begin(); it != update_to.end(); ) {
@@ -68,18 +68,19 @@ void update_entities(
6868
}
6969
}
7070
}
71-
template <typename EntityKeyType, typename EntityValueType>
72-
class EntityCollection:
73-
public std::unordered_map<const EntityKeyType *, CollectionEntry<EntityValueType>>
71+
template<typename EntityKeyType, typename EntityValueType>
72+
class EntityCollection
73+
: public std::unordered_map<const EntityKeyType *, CollectionEntry<EntityValueType>>
7474
{
7575
public:
7676
using Key = const EntityKeyType *;
7777
using EntityWeakPtr = typename EntityValueType::WeakPtr;
7878
using EntitySharedPtr = typename EntityValueType::SharedPtr;
7979

80-
void update(const EntityCollection<EntityKeyType, EntityValueType> & other,
81-
std::function<void (EntitySharedPtr)> on_added,
82-
std::function<void (EntitySharedPtr)> on_removed)
80+
void update(
81+
const EntityCollection<EntityKeyType, EntityValueType> & other,
82+
std::function<void(EntitySharedPtr)> on_added,
83+
std::function<void(EntitySharedPtr)> on_removed)
8384
{
8485
update_entities(*this, other, on_added, on_removed);
8586
}

rclcpp/include/rclcpp/executors/executor_entities_collector.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class ExecutorEntitiesCollector
6363
*/
6464
RCLCPP_PUBLIC
6565
explicit ExecutorEntitiesCollector(
66-
std::function<void(void)> on_notify_waitable_callback = {});
66+
std::function<void(void)> on_notify_waitable_callback = {});
6767

6868
/// Destructor
6969
RCLCPP_PUBLIC
@@ -172,7 +172,8 @@ class ExecutorEntitiesCollector
172172
RCLCPP_PUBLIC
173173
void
174174
add_automatically_associated_callback_groups(
175-
std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> nodes_to_check) RCPPUTILS_TSA_REQUIRES(mutex_);
175+
std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> nodes_to_check)
176+
RCPPUTILS_TSA_REQUIRES(mutex_);
176177

177178
RCLCPP_PUBLIC
178179
void

rclcpp/src/rclcpp/executors/executor_entities_collection.cpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -82,13 +82,14 @@ build_entities_collection(
8282
}
8383
}
8484

85-
template <typename EntityCollectionType>
85+
template<typename EntityCollectionType>
8686
void check_ready(
8787
EntityCollectionType & collection,
8888
std::deque<rclcpp::AnyExecutable> & executables,
8989
size_t size_of_waited_entities,
9090
typename EntityCollectionType::Key * waited_entities,
91-
std::function<bool(rclcpp::AnyExecutable, typename EntityCollectionType::EntitySharedPtr)> fill_executable)
91+
std::function<bool(rclcpp::AnyExecutable,
92+
typename EntityCollectionType::EntitySharedPtr)> fill_executable)
9293
{
9394
for (size_t ii = 0; ii < size_of_waited_entities; ++ii) {
9495
if (waited_entities[ii]) {
@@ -130,7 +131,7 @@ ready_executables(
130131
ret,
131132
rcl_wait_set.size_of_timers,
132133
rcl_wait_set.timers,
133-
[](auto exec, auto timer){
134+
[](auto exec, auto timer) {
134135
if (!timer->call()) {
135136
return false;
136137
}
@@ -143,7 +144,7 @@ ready_executables(
143144
ret,
144145
rcl_wait_set.size_of_subscriptions,
145146
rcl_wait_set.subscriptions,
146-
[](auto exec, auto subscription){
147+
[](auto exec, auto subscription) {
147148
exec.subscription = subscription;
148149
return true;
149150
});
@@ -153,7 +154,7 @@ ready_executables(
153154
ret,
154155
rcl_wait_set.size_of_services,
155156
rcl_wait_set.services,
156-
[](auto exec, auto service){
157+
[](auto exec, auto service) {
157158
exec.service = service;
158159
return true;
159160
});
@@ -163,7 +164,7 @@ ready_executables(
163164
ret,
164165
rcl_wait_set.size_of_clients,
165166
rcl_wait_set.clients,
166-
[](auto exec, auto client){
167+
[](auto exec, auto client) {
167168
exec.client = client;
168169
return true;
169170
});

rclcpp/src/rclcpp/executors/executor_entities_collector.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -24,10 +24,9 @@ namespace executors
2424
{
2525

2626
ExecutorEntitiesCollector::ExecutorEntitiesCollector(
27-
std::function<void(void)> on_notify_waitable_callback) {
28-
notify_waitable_ = std::make_shared<ExecutorNotifyWaitable>(
29-
[on_notify_waitable_callback](){on_notify_waitable_callback();});
30-
27+
std::function<void(void)> on_notify_waitable_callback)
28+
: notify_waitable_(std::make_shared<ExecutorNotifyWaitable>(on_notify_waitable_callback))
29+
{
3130
}
3231

3332
ExecutorEntitiesCollector::~ExecutorEntitiesCollector()

0 commit comments

Comments
 (0)