From 89721e9384925692d0e21b3a16f293dceab1b911 Mon Sep 17 00:00:00 2001 From: "Soragna, Alberto" Date: Mon, 12 Oct 2020 16:56:27 +0100 Subject: [PATCH] fix linter errors Signed-off-by: Soragna, Alberto --- rclcpp/include/rclcpp/executor.hpp | 6 +- .../rclcpp/executors/events_executor.hpp | 8 +- .../rclcpp/executors/timers_manager.hpp | 23 ++--- rclcpp/src/rclcpp/client.cpp | 12 +-- rclcpp/src/rclcpp/executor.cpp | 6 +- .../src/rclcpp/executors/events_executor.cpp | 89 ++++++++++--------- .../events_executor_entities_collector.cpp | 8 +- .../src/rclcpp/executors/timers_manager.cpp | 2 +- rclcpp/src/rclcpp/service.cpp | 12 +-- rclcpp/src/rclcpp/subscription_base.cpp | 12 +-- .../subscription_intra_process_base.cpp | 4 +- rclcpp/src/rclcpp/waitable.cpp | 7 +- 12 files changed, 98 insertions(+), 91 deletions(-) diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 5936d31826..c9994a49a1 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -439,15 +439,15 @@ class Executor RCLCPP_PUBLIC static void - execute_subscription(rclcpp::SubscriptionBase* subscription); + execute_subscription(rclcpp::SubscriptionBase * subscription); RCLCPP_PUBLIC static void - execute_service(rclcpp::ServiceBase* service); + execute_service(rclcpp::ServiceBase * service); RCLCPP_PUBLIC static void - execute_client(rclcpp::ClientBase* client); + execute_client(rclcpp::ClientBase * client); /** * \throws std::runtime_error if the wait set can be cleared diff --git a/rclcpp/include/rclcpp/executors/events_executor.hpp b/rclcpp/include/rclcpp/executors/events_executor.hpp index 4112362e58..dbff765279 100644 --- a/rclcpp/include/rclcpp/executors/events_executor.hpp +++ b/rclcpp/include/rclcpp/executors/events_executor.hpp @@ -132,12 +132,12 @@ class EventsExecutor : public rclcpp::Executor /// Extract and execute events from the queue until it is empty RCLCPP_PUBLIC void - consume_all_events(std::queue &queue); + consume_all_events(std::queue & queue); // Execute a single event RCLCPP_PUBLIC void - execute_event(const ExecutorEvent &event); + execute_event(const ExecutorEvent & event); // Executor callback: Push new events into the queue and trigger cv. // This function is called by the DDS entities when an event happened, @@ -146,8 +146,8 @@ class EventsExecutor : public rclcpp::Executor push_event(const void * executor_ptr, ExecutorEvent event) { // Cast executor_ptr to this (need to remove constness) - auto this_executor = const_cast( - static_cast(executor_ptr)); + auto this_executor = const_cast( + static_cast(executor_ptr)); // Event queue mutex scope { diff --git a/rclcpp/include/rclcpp/executors/timers_manager.hpp b/rclcpp/include/rclcpp/executors/timers_manager.hpp index 3418b573fa..8ef3f9a3bc 100644 --- a/rclcpp/include/rclcpp/executors/timers_manager.hpp +++ b/rclcpp/include/rclcpp/executors/timers_manager.hpp @@ -98,7 +98,7 @@ class TimersManager /** * @brief Executes one ready timer if available - * + * * @return true if there was a timer ready */ bool execute_head_timer(); @@ -106,7 +106,7 @@ class TimersManager /** * @brief Get the amount of time before the next timer expires. * - * @return std::chrono::nanoseconds to wait, + * @return std::chrono::nanoseconds to wait, * the returned value could be negative if the timer is already expired * or MAX_TIME if the heap is empty. */ @@ -131,7 +131,7 @@ class TimersManager private: RCLCPP_DISABLE_COPY(TimersManager) - using TimerPtr = rclcpp::TimerBase::SharedPtr*; + using TimerPtr = rclcpp::TimerBase::SharedPtr *; /** * @brief Implements a loop that keeps executing ready timers. @@ -143,7 +143,7 @@ class TimersManager * @brief Get the amount of time before the next timer expires. * This function is not thread safe, acquire a mutex before calling it. * - * @return std::chrono::nanoseconds to wait, + * @return std::chrono::nanoseconds to wait, * the returned value could be negative if the timer is already expired * or MAX_TIME if the heap is empty. */ @@ -194,10 +194,13 @@ class TimersManager { size_t i = heap_.size(); // Position where we are going to add timer heap_.push_back(x); - while (i && ((*x)->time_until_trigger() < (*heap_[(i-1)/2])->time_until_trigger())) { - heap_[i] = heap_[(i-1)/2]; - heap_[(i-1)/2] = x; - i = (i-1)/2; + + size_t parent = (i - 1) / 2; + while (i > 0 && ((*x)->time_until_trigger() < (*heap_[parent])->time_until_trigger())) { + heap_[i] = heap_[parent]; + heap_[parent] = x; + i = parent; + parent = (i - 1) / 2; } } @@ -225,12 +228,12 @@ class TimersManager } heap_[i] = heap_[left_child]; i = left_child; - left_child = 2*i + 1; + left_child = 2 * i + 1; } // Swim down while (i > start) { - size_t parent = (i - 1)/2; + size_t parent = (i - 1) / 2; if ((*updated_timer)->time_until_trigger() < (*heap_[parent])->time_until_trigger()) { heap_[i] = heap_[parent]; i = parent; diff --git a/rclcpp/src/rclcpp/client.cpp b/rclcpp/src/rclcpp/client.cpp index f4cfc40b31..905b5fdbba 100644 --- a/rclcpp/src/rclcpp/client.cpp +++ b/rclcpp/src/rclcpp/client.cpp @@ -201,14 +201,14 @@ ClientBase::exchange_in_use_by_wait_set_state(bool in_use_state) void ClientBase::set_events_executor_callback( - const void * executor_context, - ExecutorEventCallback executor_callback) const + const void * executor_context, + ExecutorEventCallback executor_callback) const { rcl_ret_t ret = rcl_client_set_events_executor_callback( - executor_context, - executor_callback, - this, - client_handle_.get()); + executor_context, + executor_callback, + this, + client_handle_.get()); if (RCL_RET_OK != ret) { throw std::runtime_error(std::string("Couldn't set client callback")); diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 12225e3cef..be138fc487 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -561,7 +561,7 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription) } void -Executor::execute_subscription(rclcpp::SubscriptionBase* subscription) +Executor::execute_subscription(rclcpp::SubscriptionBase * subscription) { rclcpp::MessageInfo message_info; message_info.get_rmw_message_info().from_intra_process = false; @@ -641,7 +641,7 @@ Executor::execute_service(rclcpp::ServiceBase::SharedPtr service) } void -Executor::execute_service(rclcpp::ServiceBase* service) +Executor::execute_service(rclcpp::ServiceBase * service) { auto request_header = service->create_request_header(); std::shared_ptr request = service->create_request(); @@ -659,7 +659,7 @@ Executor::execute_client(rclcpp::ClientBase::SharedPtr client) } void -Executor::execute_client(rclcpp::ClientBase* client) +Executor::execute_client(rclcpp::ClientBase * client) { auto request_header = client->create_request_header(); std::shared_ptr response = client->create_response(); diff --git a/rclcpp/src/rclcpp/executors/events_executor.cpp b/rclcpp/src/rclcpp/executors/events_executor.cpp index 099ed64340..6f81915dd3 100644 --- a/rclcpp/src/rclcpp/executors/events_executor.cpp +++ b/rclcpp/src/rclcpp/executors/events_executor.cpp @@ -14,6 +14,7 @@ #include #include +#include #include #include "rclcpp/executors/events_executor.hpp" @@ -112,7 +113,7 @@ EventsExecutor::spin_some(std::chrono::nanoseconds max_duration) throw std::runtime_error("spin_some() called while already spinning"); } RCLCPP_SCOPE_EXIT(this->spinning.store(false);); - + // This function will wait until the first of the following events occur: // - The input max_duration is elapsed // - A timer triggers @@ -251,7 +252,7 @@ EventsExecutor::add_node( timers_manager_->add_timer(timer); } return false; - }); + }); // Set the callbacks to all the entities group->find_subscription_ptrs_if( [this](const rclcpp::SubscriptionBase::SharedPtr & subscription) { @@ -286,11 +287,11 @@ EventsExecutor::add_node( // Set node's guard condition callback, so if new entities are added while // spinning we can set their callback. rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( - this, - &EventsExecutor::push_event, - entities_collector_.get(), - node_ptr->get_notify_guard_condition(), - false /* Discard previous events */); + this, + &EventsExecutor::push_event, + entities_collector_.get(), + node_ptr->get_notify_guard_condition(), + false /* Discard previous events */); if (ret != RCL_RET_OK) { throw std::runtime_error("Couldn't set node guard condition callback"); @@ -321,7 +322,7 @@ EventsExecutor::remove_node(std::shared_ptr node_ptr, bool notify) } void -EventsExecutor::consume_all_events(std::queue &event_queue) +EventsExecutor::consume_all_events(std::queue & event_queue) { while (!event_queue.empty()) { ExecutorEvent event = event_queue.front(); @@ -332,43 +333,43 @@ EventsExecutor::consume_all_events(std::queue &event_queue) } void -EventsExecutor::execute_event(const ExecutorEvent &event) +EventsExecutor::execute_event(const ExecutorEvent & event) { - switch(event.type) { - case SUBSCRIPTION_EVENT: - { - auto subscription = const_cast( - static_cast(event.entity)); - execute_subscription(subscription); - break; - } - - case SERVICE_EVENT: - { - auto service = const_cast( - static_cast(event.entity)); - execute_service(service); - break; - } - - case CLIENT_EVENT: - { - auto client = const_cast( - static_cast(event.entity)); - execute_client(client); + switch (event.type) { + case SUBSCRIPTION_EVENT: + { + auto subscription = const_cast( + static_cast(event.entity)); + execute_subscription(subscription); + break; + } + + case SERVICE_EVENT: + { + auto service = const_cast( + static_cast(event.entity)); + execute_service(service); + break; + } + + case CLIENT_EVENT: + { + auto client = const_cast( + static_cast(event.entity)); + execute_client(client); + break; + } + + case WAITABLE_EVENT: + { + auto waitable = const_cast( + static_cast(event.entity)); + waitable->execute(); + break; + } + + default: + throw std::runtime_error("EventsExecutor received unrecognized event"); break; - } - - case WAITABLE_EVENT: - { - auto waitable = const_cast( - static_cast(event.entity)); - waitable->execute(); - break; - } - - default: - throw std::runtime_error("EventsExecutor received unrecognized event"); - break; } } diff --git a/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp b/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp index 92e8cd38ce..e09c3b642b 100644 --- a/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp +++ b/rclcpp/src/rclcpp/executors/events_executor_entities_collector.cpp @@ -62,7 +62,7 @@ EventsExecutorEntitiesCollector::execute() void EventsExecutorEntitiesCollector::add_node( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) { // If the node already has an executor std::atomic_bool & has_executor = node_ptr->get_associated_with_executor_atomic(); @@ -86,9 +86,9 @@ EventsExecutorEntitiesCollector::remove_node( if (matched) { // Node found: unset its entities callbacks rcl_ret_t ret = rcl_guard_condition_set_events_executor_callback( - nullptr, nullptr, nullptr, - node_ptr->get_notify_guard_condition(), - false); + nullptr, nullptr, nullptr, + node_ptr->get_notify_guard_condition(), + false); if (ret != RCL_RET_OK) { throw std::runtime_error(std::string("Couldn't set guard condition callback")); diff --git a/rclcpp/src/rclcpp/executors/timers_manager.cpp b/rclcpp/src/rclcpp/executors/timers_manager.cpp index 9088221348..1652ebbb21 100644 --- a/rclcpp/src/rclcpp/executors/timers_manager.cpp +++ b/rclcpp/src/rclcpp/executors/timers_manager.cpp @@ -164,7 +164,7 @@ void TimersManager::remove_timer(rclcpp::TimerBase::SharedPtr timer) void TimersManager::rebuild_heap() { heap_.clear(); - for (auto& t : timers_storage_) { + for (auto & t : timers_storage_) { this->add_timer_to_heap(&t); } } diff --git a/rclcpp/src/rclcpp/service.cpp b/rclcpp/src/rclcpp/service.cpp index a178314e91..ee2865f067 100644 --- a/rclcpp/src/rclcpp/service.cpp +++ b/rclcpp/src/rclcpp/service.cpp @@ -87,14 +87,14 @@ ServiceBase::exchange_in_use_by_wait_set_state(bool in_use_state) void ServiceBase::set_events_executor_callback( - const void * executor_context, - ExecutorEventCallback executor_callback) const + const void * executor_context, + ExecutorEventCallback executor_callback) const { rcl_ret_t ret = rcl_service_set_events_executor_callback( - executor_context, - executor_callback, - this, - service_handle_.get()); + executor_context, + executor_callback, + this, + service_handle_.get()); if (RCL_RET_OK != ret) { throw std::runtime_error(std::string("Couldn't set service callback")); diff --git a/rclcpp/src/rclcpp/subscription_base.cpp b/rclcpp/src/rclcpp/subscription_base.cpp index 073168748e..e163f32c0a 100644 --- a/rclcpp/src/rclcpp/subscription_base.cpp +++ b/rclcpp/src/rclcpp/subscription_base.cpp @@ -291,14 +291,14 @@ SubscriptionBase::exchange_in_use_by_wait_set_state( void SubscriptionBase::set_events_executor_callback( - const void * executor_context, - ExecutorEventCallback executor_callback) const + const void * executor_context, + ExecutorEventCallback executor_callback) const { rcl_ret_t ret = rcl_subscription_set_events_executor_callback( - executor_context, - executor_callback, - this, - subscription_handle_.get()); + executor_context, + executor_callback, + this, + subscription_handle_.get()); if (RCL_RET_OK != ret) { throw std::runtime_error(std::string("Couldn't set subscription callback")); diff --git a/rclcpp/src/rclcpp/subscription_intra_process_base.cpp b/rclcpp/src/rclcpp/subscription_intra_process_base.cpp index 067cadf7eb..ae2bad93f4 100644 --- a/rclcpp/src/rclcpp/subscription_intra_process_base.cpp +++ b/rclcpp/src/rclcpp/subscription_intra_process_base.cpp @@ -12,6 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include + #include "rclcpp/experimental/subscription_intra_process_base.hpp" using rclcpp::experimental::SubscriptionIntraProcessBase; @@ -52,4 +54,4 @@ SubscriptionIntraProcessBase::set_events_executor_callback( if (RCL_RET_OK != ret) { throw std::runtime_error(std::string("Couldn't set guard condition callback")); } -} \ No newline at end of file +} diff --git a/rclcpp/src/rclcpp/waitable.cpp b/rclcpp/src/rclcpp/waitable.cpp index f354145a79..a266c91eb7 100644 --- a/rclcpp/src/rclcpp/waitable.cpp +++ b/rclcpp/src/rclcpp/waitable.cpp @@ -62,11 +62,12 @@ Waitable::exchange_in_use_by_wait_set_state(bool in_use_state) void Waitable::set_events_executor_callback( - void * executor_context, - ExecutorEventCallback executor_callback) const + void * executor_context, + ExecutorEventCallback executor_callback) const { (void)executor_context; (void)executor_callback; - throw std::runtime_error("Custom waitables should override set_events_executor_callback() to use events executor"); + throw std::runtime_error( + "Custom waitables should override set_events_executor_callback() to use events executor"); }