From 38c750b87610e6c424026ca4154379ec055e83ba Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Thu, 28 Sep 2017 11:57:18 -0700 Subject: [PATCH] update style to match latest uncrustify --- .../rclcpp/allocator/allocator_common.hpp | 10 +++--- .../include/rclcpp/any_service_callback.hpp | 6 ++-- rclcpp/include/rclcpp/client.hpp | 3 +- rclcpp/include/rclcpp/exceptions.hpp | 2 +- rclcpp/include/rclcpp/executor.hpp | 6 ++-- .../include/rclcpp/intra_process_manager.hpp | 20 ++++++----- .../rclcpp/intra_process_manager_impl.hpp | 21 ++++++++---- rclcpp/include/rclcpp/memory_strategy.hpp | 18 ++++++---- .../node_parameters_interface.hpp | 4 +-- rclcpp/include/rclcpp/publisher.hpp | 2 +- rclcpp/include/rclcpp/scope_exit.hpp | 4 +-- rclcpp/include/rclcpp/service.hpp | 3 +- .../strategies/allocator_memory_strategy.hpp | 6 ++-- rclcpp/include/rclcpp/subscription.hpp | 2 +- .../include/rclcpp/subscription_factory.hpp | 3 +- rclcpp/src/rclcpp/exceptions.cpp | 2 +- .../rclcpp/expand_topic_or_service_name.cpp | 7 ++-- rclcpp/src/rclcpp/graph_listener.cpp | 13 +++---- rclcpp/src/rclcpp/memory_strategy.cpp | 9 +++-- rclcpp/src/rclcpp/node.cpp | 3 +- .../src/rclcpp/node_interfaces/node_base.cpp | 16 +++++---- .../src/rclcpp/node_interfaces/node_graph.cpp | 4 +-- .../node_interfaces/node_parameters.cpp | 34 +++++++++---------- rclcpp/src/rclcpp/utilities.cpp | 14 ++++---- .../test/test_externally_defined_services.cpp | 3 +- .../type_traits/is_manageable_node.hpp | 18 ++++++---- rclcpp_lifecycle/src/lifecycle_node.cpp | 3 +- .../src/lifecycle_node_interface_impl.hpp | 15 +++++--- 28 files changed, 151 insertions(+), 100 deletions(-) diff --git a/rclcpp/include/rclcpp/allocator/allocator_common.hpp b/rclcpp/include/rclcpp/allocator/allocator_common.hpp index dccfe4f..1e60f7f 100644 --- a/rclcpp/include/rclcpp/allocator/allocator_common.hpp +++ b/rclcpp/include/rclcpp/allocator/allocator_common.hpp @@ -64,8 +64,9 @@ void * retyped_reallocate(void * untyped_pointer, size_t size, void * untyped_al // Convert a std::allocator_traits-formatted Allocator into an rcl allocator -template>::value>::type * = nullptr> +template< + typename T, typename Alloc, + typename std::enable_if>::value>::type * = nullptr> rcl_allocator_t get_rcl_allocator(Alloc & allocator) { rcl_allocator_t rcl_allocator = rcl_get_default_allocator(); @@ -81,8 +82,9 @@ rcl_allocator_t get_rcl_allocator(Alloc & allocator) } // TODO(jacquelinekay) Workaround for an incomplete implementation of std::allocator -template>::value>::type * = nullptr> +template< + typename T, typename Alloc, + typename std::enable_if>::value>::type * = nullptr> rcl_allocator_t get_rcl_allocator(Alloc & allocator) { (void)allocator; diff --git a/rclcpp/include/rclcpp/any_service_callback.hpp b/rclcpp/include/rclcpp/any_service_callback.hpp index 076cc5a..ae9072c 100644 --- a/rclcpp/include/rclcpp/any_service_callback.hpp +++ b/rclcpp/include/rclcpp/any_service_callback.hpp @@ -34,11 +34,13 @@ template class AnyServiceCallback { private: - using SharedPtrCallback = std::function, std::shared_ptr )>; - using SharedPtrWithRequestHeaderCallback = std::function, const std::shared_ptr, std::shared_ptr diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 482d29b..0816a2d 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -193,7 +193,8 @@ public: } void - handle_response(std::shared_ptr request_header, + handle_response( + std::shared_ptr request_header, std::shared_ptr response) { std::lock_guard lock(pending_requests_mutex_); diff --git a/rclcpp/include/rclcpp/exceptions.hpp b/rclcpp/include/rclcpp/exceptions.hpp index 9b6eb11..23da40e 100644 --- a/rclcpp/include/rclcpp/exceptions.hpp +++ b/rclcpp/include/rclcpp/exceptions.hpp @@ -116,7 +116,7 @@ throw_from_rcl_error( rcl_ret_t ret, const std::string & prefix = "", const rcl_error_state_t * error_state = nullptr, - void (* reset_error)() = rcl_reset_error); + void (*reset_error)() = rcl_reset_error); class RCLErrorBase { diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 13392fb..7ddcc57 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -151,7 +151,8 @@ public: */ template void - spin_node_once(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, + spin_node_once( + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( @@ -163,7 +164,8 @@ public: /// Convenience function which takes Node and forwards NodeBaseInterface. template void - spin_node_once(std::shared_ptr node, + spin_node_once( + std::shared_ptr node, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( diff --git a/rclcpp/include/rclcpp/intra_process_manager.hpp b/rclcpp/include/rclcpp/intra_process_manager.hpp index 2a349f6..69e5d5e 100644 --- a/rclcpp/include/rclcpp/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager.hpp @@ -186,14 +186,16 @@ public: */ template uint64_t - add_publisher(typename publisher::Publisher::SharedPtr publisher, + add_publisher( + typename publisher::Publisher::SharedPtr publisher, size_t buffer_size = 0) { auto id = IntraProcessManager::get_next_unique_id(); size_t size = buffer_size > 0 ? buffer_size : publisher->get_queue_size(); - auto mrb = mapped_ring_buffer::MappedRingBuffer::MessageAlloc>::make_shared( - size, publisher->get_allocator()); + auto mrb = mapped_ring_buffer::MappedRingBuffer< + MessageT, + typename publisher::Publisher::MessageAlloc + >::make_shared(size, publisher->get_allocator()); impl_->add_publisher(id, publisher, mrb, size); return id; } @@ -239,8 +241,9 @@ public: * \param message the message that is being stored. * \return the message sequence number. */ - template, - typename Deleter = std::default_delete> + template< + typename MessageT, typename Alloc = std::allocator, + typename Deleter = std::default_delete> uint64_t store_intra_process_message( uint64_t intra_process_publisher_id, @@ -302,8 +305,9 @@ public: * \param requesting_subscriptions_intra_process_id the subscription's id. * \param message the message typed unique_ptr used to return the message. */ - template, - typename Deleter = std::default_delete> + template< + typename MessageT, typename Alloc = std::allocator, + typename Deleter = std::default_delete> void take_intra_process_message( uint64_t intra_process_publisher_id, diff --git a/rclcpp/include/rclcpp/intra_process_manager_impl.hpp b/rclcpp/include/rclcpp/intra_process_manager_impl.hpp index 0317c33..8ffba74 100644 --- a/rclcpp/include/rclcpp/intra_process_manager_impl.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager_impl.hpp @@ -53,7 +53,8 @@ public: virtual void remove_subscription(uint64_t intra_process_subscription_id) = 0; - virtual void add_publisher(uint64_t id, + virtual void add_publisher( + uint64_t id, publisher::PublisherBase::WeakPtr publisher, mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb, size_t size) = 0; @@ -70,7 +71,8 @@ public: store_intra_process_message(uint64_t intra_process_publisher_id, uint64_t message_seq) = 0; virtual mapped_ring_buffer::MappedRingBufferBase::SharedPtr - take_intra_process_message(uint64_t intra_process_publisher_id, + take_intra_process_message( + uint64_t intra_process_publisher_id, uint64_t message_sequence_number, uint64_t requesting_subscriptions_intra_process_id, size_t & size) = 0; @@ -114,7 +116,8 @@ public: } } - void add_publisher(uint64_t id, + void add_publisher( + uint64_t id, publisher::PublisherBase::WeakPtr publisher, mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb, size_t size) @@ -189,7 +192,8 @@ public: } mapped_ring_buffer::MappedRingBufferBase::SharedPtr - take_intra_process_message(uint64_t intra_process_publisher_id, + take_intra_process_message( + uint64_t intra_process_publisher_id, uint64_t message_sequence_number, uint64_t requesting_subscriptions_intra_process_id, size_t & size @@ -253,7 +257,8 @@ private: RebindAlloc uint64_allocator; using AllocSet = std::set, RebindAlloc>; - using SubscriptionMap = std::unordered_map, std::equal_to, RebindAlloc>>; @@ -285,13 +290,15 @@ private: std::atomic sequence_number; mapped_ring_buffer::MappedRingBufferBase::SharedPtr buffer; - using TargetSubscriptionsMap = std::unordered_map, std::equal_to, RebindAlloc>>; TargetSubscriptionsMap target_subscriptions_by_message_sequence; }; - using PublisherMap = std::unordered_map, std::equal_to, RebindAlloc>>; diff --git a/rclcpp/include/rclcpp/memory_strategy.hpp b/rclcpp/include/rclcpp/memory_strategy.hpp index cecc723..bc9c87b 100644 --- a/rclcpp/include/rclcpp/memory_strategy.hpp +++ b/rclcpp/include/rclcpp/memory_strategy.hpp @@ -64,22 +64,26 @@ public: virtual void remove_guard_condition(const rcl_guard_condition_t * guard_condition) = 0; virtual void - get_next_subscription(rclcpp::executor::AnyExecutable::SharedPtr any_exec, + get_next_subscription( + rclcpp::executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector & weak_nodes) = 0; virtual void - get_next_service(rclcpp::executor::AnyExecutable::SharedPtr any_exec, + get_next_service( + rclcpp::executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector & weak_nodes) = 0; virtual void - get_next_client(rclcpp::executor::AnyExecutable::SharedPtr any_exec, + get_next_client( + rclcpp::executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector & weak_nodes) = 0; virtual rcl_allocator_t get_allocator() = 0; static rclcpp::subscription::SubscriptionBase::SharedPtr - get_subscription_by_handle(const rcl_subscription_t * subscriber_handle, + get_subscription_by_handle( + const rcl_subscription_t * subscriber_handle, const WeakNodeVector & weak_nodes); static rclcpp::service::ServiceBase::SharedPtr @@ -89,7 +93,8 @@ public: get_client_by_handle(const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes); static rclcpp::node_interfaces::NodeBaseInterface::SharedPtr - get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group, + get_node_by_group( + rclcpp::callback_group::CallbackGroup::SharedPtr group, const WeakNodeVector & weak_nodes); static rclcpp::callback_group::CallbackGroup::SharedPtr @@ -103,7 +108,8 @@ public: const WeakNodeVector & weak_nodes); static rclcpp::callback_group::CallbackGroup::SharedPtr - get_group_by_client(rclcpp::client::ClientBase::SharedPtr client, + get_group_by_client( + rclcpp::client::ClientBase::SharedPtr client, const WeakNodeVector & weak_nodes); }; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp index b2e9b43..c936728 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp @@ -81,8 +81,8 @@ public: rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector & prefixes, uint64_t depth) const = 0; - using ParametersCallbackFunction = - std::function &)>; RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index ce6a91e..d6b4636 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -50,7 +50,7 @@ namespace publisher class PublisherBase { - friend rclcpp::node_interfaces::NodeTopicsInterface; + friend ::rclcpp::node_interfaces::NodeTopicsInterface; public: RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase) diff --git a/rclcpp/include/rclcpp/scope_exit.hpp b/rclcpp/include/rclcpp/scope_exit.hpp index 334b790..7865de5 100644 --- a/rclcpp/include/rclcpp/scope_exit.hpp +++ b/rclcpp/include/rclcpp/scope_exit.hpp @@ -31,7 +31,7 @@ struct ScopeExit { explicit ScopeExit(Callable callable) : callable_(callable) {} - ~ScopeExit() {callable_(); } + ~ScopeExit() {callable_();} private: Callable callable_; @@ -47,6 +47,6 @@ make_scope_exit(Callable callable) } // namespace rclcpp #define RCLCPP_SCOPE_EXIT(code) \ - auto RCLCPP_STRING_JOIN(scope_exit_, __LINE__) = rclcpp::make_scope_exit([&]() {code; }) + auto RCLCPP_STRING_JOIN(scope_exit_, __LINE__) = rclcpp::make_scope_exit([&]() {code;}) #endif // RCLCPP__SCOPE_EXIT_HPP_ diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index f05b58f..0b05dcb 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -196,7 +196,8 @@ public: return std::shared_ptr(new rmw_request_id_t); } - void handle_request(std::shared_ptr request_header, + void handle_request( + std::shared_ptr request_header, std::shared_ptr request) { auto typed_request = std::static_pointer_cast(request); diff --git a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp index 1cac9a5..68e6644 100644 --- a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp @@ -231,7 +231,8 @@ public: } virtual void - get_next_subscription(executor::AnyExecutable::SharedPtr any_exec, + get_next_subscription( + executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector & weak_nodes) { auto it = subscription_handles_.begin(); @@ -274,7 +275,8 @@ public: } virtual void - get_next_service(executor::AnyExecutable::SharedPtr any_exec, + get_next_service( + executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector & weak_nodes) { auto it = service_handles_.begin(); diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 6f081af..8471530 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -285,7 +285,7 @@ private: AnySubscriptionCallback any_callback_; typename message_memory_strategy::MessageMemoryStrategy::SharedPtr - message_memory_strategy_; + message_memory_strategy_; GetMessageCallbackType get_intra_process_message_callback_; MatchesAnyPublishersCallbackType matches_any_intra_process_publishers_; diff --git a/rclcpp/include/rclcpp/subscription_factory.hpp b/rclcpp/include/rclcpp/subscription_factory.hpp index 16af304..0173503 100644 --- a/rclcpp/include/rclcpp/subscription_factory.hpp +++ b/rclcpp/include/rclcpp/subscription_factory.hpp @@ -55,7 +55,8 @@ struct SubscriptionFactory SubscriptionFactoryFunction create_typed_subscription; // Function that takes a MessageT from the intra process manager - using SetupIntraProcessFunction = std::function; diff --git a/rclcpp/src/rclcpp/exceptions.cpp b/rclcpp/src/rclcpp/exceptions.cpp index b10523c..bbaa83b 100644 --- a/rclcpp/src/rclcpp/exceptions.cpp +++ b/rclcpp/src/rclcpp/exceptions.cpp @@ -44,7 +44,7 @@ throw_from_rcl_error( rcl_ret_t ret, const std::string & prefix, const rcl_error_state_t * error_state, - void (* reset_error)()) + void (*reset_error)()) { if (RCL_RET_OK == ret) { throw std::invalid_argument("ret is RCL_RET_OK"); diff --git a/rclcpp/src/rclcpp/expand_topic_or_service_name.cpp b/rclcpp/src/rclcpp/expand_topic_or_service_name.cpp index 371c7ba..7b42309 100644 --- a/rclcpp/src/rclcpp/expand_topic_or_service_name.cpp +++ b/rclcpp/src/rclcpp/expand_topic_or_service_name.cpp @@ -54,9 +54,10 @@ rclcpp::expand_topic_or_service_name( if (rcutils_error_state_copy(rcl_get_error_state(), &error_state) != RCUTILS_RET_OK) { throw std::bad_alloc(); } - auto error_state_scope_exit = rclcpp::make_scope_exit([&error_state]() { - rcutils_error_state_fini(&error_state); - }); + auto error_state_scope_exit = rclcpp::make_scope_exit( + [&error_state]() { + rcutils_error_state_fini(&error_state); + }); // finalize the string map before throwing rcutils_ret = rcutils_string_map_fini(&substitutions_map); if (rcutils_ret != RCUTILS_RET_OK) { diff --git a/rclcpp/src/rclcpp/graph_listener.cpp b/rclcpp/src/rclcpp/graph_listener.cpp index 6d24158..843f4bb 100644 --- a/rclcpp/src/rclcpp/graph_listener.cpp +++ b/rclcpp/src/rclcpp/graph_listener.cpp @@ -75,12 +75,13 @@ GraphListener::start_if_not_started() // This is important to ensure that the wait set is finalized before // destruction of static objects occurs. std::weak_ptr weak_this = shared_from_this(); - rclcpp::utilities::on_shutdown([weak_this]() { - auto shared_this = weak_this.lock(); - if (shared_this) { - shared_this->shutdown(); - } - }); + rclcpp::utilities::on_shutdown( + [weak_this]() { + auto shared_this = weak_this.lock(); + if (shared_this) { + shared_this->shutdown(); + } + }); // Start the listener thread. listener_thread_ = std::thread(&GraphListener::run, this); is_started_ = true; diff --git a/rclcpp/src/rclcpp/memory_strategy.cpp b/rclcpp/src/rclcpp/memory_strategy.cpp index 61b8432..3a0db98 100644 --- a/rclcpp/src/rclcpp/memory_strategy.cpp +++ b/rclcpp/src/rclcpp/memory_strategy.cpp @@ -47,7 +47,8 @@ MemoryStrategy::get_subscription_by_handle( } rclcpp::service::ServiceBase::SharedPtr -MemoryStrategy::get_service_by_handle(const rcl_service_t * service_handle, +MemoryStrategy::get_service_by_handle( + const rcl_service_t * service_handle, const WeakNodeVector & weak_nodes) { for (auto & weak_node : weak_nodes) { @@ -72,7 +73,8 @@ MemoryStrategy::get_service_by_handle(const rcl_service_t * service_handle, } rclcpp::client::ClientBase::SharedPtr -MemoryStrategy::get_client_by_handle(const rcl_client_t * client_handle, +MemoryStrategy::get_client_by_handle( + const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes) { for (auto & weak_node : weak_nodes) { @@ -97,7 +99,8 @@ MemoryStrategy::get_client_by_handle(const rcl_client_t * client_handle, } rclcpp::node_interfaces::NodeBaseInterface::SharedPtr -MemoryStrategy::get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group, +MemoryStrategy::get_node_by_group( + rclcpp::callback_group::CallbackGroup::SharedPtr group, const WeakNodeVector & weak_nodes) { if (!group) { diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index 09d3084..6d8163c 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -117,7 +117,8 @@ Node::get_parameter(const std::string & name) const return node_parameters_->get_parameter(name); } -bool Node::get_parameter(const std::string & name, +bool Node::get_parameter( + const std::string & name, rclcpp::parameter::ParameterVariant & parameter) const { return node_parameters_->get_parameter(name, parameter); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp index f5cbed4..b960dcd 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp @@ -133,13 +133,15 @@ NodeBase::NodeBase( throw_from_rcl_error(ret, "failed to initialize rcl node"); } - node_handle_.reset(rcl_node, [](rcl_node_t * node) -> void { - if (rcl_node_fini(node) != RCL_RET_OK) { - fprintf( - stderr, "Error in destruction of rcl node handle: %s\n", rcl_get_error_string_safe()); - } - delete node; - }); + node_handle_.reset( + rcl_node, + [](rcl_node_t * node) -> void { + if (rcl_node_fini(node) != RCL_RET_OK) { + fprintf( + stderr, "Error in destruction of rcl node handle: %s\n", rcl_get_error_string_safe()); + } + delete node; + }); // Create the default callback group. using rclcpp::callback_group::CallbackGroupType; diff --git a/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp b/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp index d9f940e..f04f0c8 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_graph.cpp @@ -234,8 +234,8 @@ NodeGraph::notify_graph_change() graph_events_.begin(), graph_events_.end(), [](const rclcpp::event::Event::WeakPtr & wptr) { - return wptr.expired(); - }), + return wptr.expired(); + }), graph_events_.end()); // update graph_users_count_ graph_users_count_.store(graph_events_.size()); diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 0660f6c..c3a6805 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -119,8 +119,8 @@ NodeParameters::get_parameters(const std::vector & names) const for (auto & name : names) { if (std::any_of(parameters_.cbegin(), parameters_.cend(), [&name](const std::pair & kv) { - return name == kv.first; - })) + return name == kv.first; + })) { results.push_back(parameters_.at(name)); } @@ -162,8 +162,8 @@ NodeParameters::describe_parameters(const std::vector & names) cons std::vector results; for (auto & kv : parameters_) { if (std::any_of(names.cbegin(), names.cend(), [&kv](const std::string & name) { - return name == kv.first; - })) + return name == kv.first; + })) { rcl_interfaces::msg::ParameterDescriptor parameter_descriptor; parameter_descriptor.name = kv.first; @@ -181,8 +181,8 @@ NodeParameters::get_parameter_types(const std::vector & names) cons std::vector results; for (auto & kv : parameters_) { if (std::any_of(names.cbegin(), names.cend(), [&kv](const std::string & name) { - return name == kv.first; - })) + return name == kv.first; + })) { results.push_back(kv.second.get_type()); } else { @@ -207,17 +207,17 @@ NodeParameters::list_parameters(const std::vector & prefixes, uint6 (static_cast(std::count(kv.first.begin(), kv.first.end(), separator)) < depth)); bool prefix_matches = std::any_of(prefixes.cbegin(), prefixes.cend(), [&kv, &depth, &separator](const std::string & prefix) { - if (kv.first == prefix) { - return true; - } else if (kv.first.find(prefix + separator) == 0) { - size_t length = prefix.length(); - std::string substr = kv.first.substr(length); - // Cast as unsigned integer to avoid warning - return (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) || - (static_cast(std::count(substr.begin(), substr.end(), separator)) < depth); - } - return false; - }); + if (kv.first == prefix) { + return true; + } else if (kv.first.find(prefix + separator) == 0) { + size_t length = prefix.length(); + std::string substr = kv.first.substr(length); + // Cast as unsigned integer to avoid warning + return (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) || + (static_cast(std::count(substr.begin(), substr.end(), separator)) < depth); + } + return false; + }); if (get_all || prefix_matches) { result.names.push_back(kv.first); size_t last_separator = kv.first.find_last_of(separator); diff --git a/rclcpp/src/rclcpp/utilities.cpp b/rclcpp/src/rclcpp/utilities.cpp index 7894407..e0a0d02 100644 --- a/rclcpp/src/rclcpp/utilities.cpp +++ b/rclcpp/src/rclcpp/utilities.cpp @@ -176,15 +176,17 @@ rclcpp::utilities::init(int argc, char * argv[]) action.sa_flags = SA_SIGINFO; ::old_action = set_sigaction(SIGINT, action); // Register an on_shutdown hook to restore the old action. - rclcpp::utilities::on_shutdown([]() { - set_sigaction(SIGINT, ::old_action); - }); + rclcpp::utilities::on_shutdown( + []() { + set_sigaction(SIGINT, ::old_action); + }); #else ::old_signal_handler = set_signal_handler(SIGINT, ::signal_handler); // Register an on_shutdown hook to restore the old signal handler. - rclcpp::utilities::on_shutdown([]() { - set_signal_handler(SIGINT, ::old_signal_handler); - }); + rclcpp::utilities::on_shutdown( + []() { + set_signal_handler(SIGINT, ::old_signal_handler); + }); #endif } diff --git a/rclcpp/test/test_externally_defined_services.cpp b/rclcpp/test/test_externally_defined_services.cpp index fc431b4..3c3aec9 100644 --- a/rclcpp/test/test_externally_defined_services.cpp +++ b/rclcpp/test/test_externally_defined_services.cpp @@ -37,7 +37,8 @@ protected: }; void -callback(const std::shared_ptr/*req*/, +callback( + const std::shared_ptr/*req*/, std::shared_ptr/*resp*/) {} diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/type_traits/is_manageable_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/type_traits/is_manageable_node.hpp index c8eeb42..1a5313a 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/type_traits/is_manageable_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/type_traits/is_manageable_node.hpp @@ -25,8 +25,10 @@ struct has_on_activate }; template -struct has_on_activate().on_activate())>::value>::type> +struct has_on_activate< + T, + typename std::enable_if< + std::is_same().on_activate())>::value>::type> { static constexpr bool value = true; }; @@ -38,8 +40,10 @@ struct has_on_deactivate }; template -struct has_on_deactivate().on_deactivate())>::value>::type> +struct has_on_deactivate< + T, + typename std::enable_if< + std::is_same().on_deactivate())>::value>::type> { static constexpr bool value = true; }; @@ -49,8 +53,10 @@ struct is_manageable_node : std::false_type {}; template -struct is_manageable_node::value && has_on_deactivate::value>::type>: std::true_type +struct is_manageable_node< + T, + typename std::enable_if< + has_on_activate::value && has_on_deactivate::value>::type>: std::true_type {}; #endif // RCLCPP_LIFECYCLE__TYPE_TRAITS__IS_MANAGEABLE_NODE_HPP_ diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index e05f80b..ad5bd26 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -135,7 +135,8 @@ LifecycleNode::get_parameter(const std::string & name) const return node_parameters_->get_parameter(name); } -bool LifecycleNode::get_parameter(const std::string & name, +bool LifecycleNode::get_parameter( + const std::string & name, rclcpp::parameter::ParameterVariant & parameter) const { return node_parameters_->get_parameter(name, parameter); diff --git a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp index adf10f3..7742e75 100644 --- a/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp +++ b/rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp @@ -164,7 +164,8 @@ public: } bool - register_callback(std::uint8_t lifecycle_transition, std::function & cb) { cb_map_[lifecycle_transition] = cb; @@ -172,7 +173,8 @@ public: } void - on_change_state(const std::shared_ptr header, + on_change_state( + const std::shared_ptr header, const std::shared_ptr req, std::shared_ptr resp) { @@ -192,7 +194,8 @@ public: } void - on_get_state(const std::shared_ptr header, + on_get_state( + const std::shared_ptr header, const std::shared_ptr req, std::shared_ptr resp) { @@ -207,7 +210,8 @@ public: } void - on_get_available_states(const std::shared_ptr header, + on_get_available_states( + const std::shared_ptr header, const std::shared_ptr req, std::shared_ptr resp) { @@ -226,7 +230,8 @@ public: } void - on_get_available_transitions(const std::shared_ptr header, + on_get_available_transitions( + const std::shared_ptr header, const std::shared_ptr req, std::shared_ptr resp) {