Skip to content

Commit

Permalink
Merge pull request ros2#6 from alsora/asoragna/linter-errors
Browse files Browse the repository at this point in the history
fix linter errors
  • Loading branch information
iRobot ROS authored Oct 12, 2020
2 parents eb0bb01 + 89721e9 commit 2037ee5
Show file tree
Hide file tree
Showing 12 changed files with 98 additions and 91 deletions.
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/executors/events_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ExecutorEvent> &queue);
consume_all_events(std::queue<ExecutorEvent> & 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,
Expand All @@ -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<executors::EventsExecutor*>(
static_cast<const executors::EventsExecutor*>(executor_ptr));
auto this_executor = const_cast<executors::EventsExecutor *>(
static_cast<const executors::EventsExecutor *>(executor_ptr));

// Event queue mutex scope
{
Expand Down
23 changes: 13 additions & 10 deletions rclcpp/include/rclcpp/executors/timers_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,15 +98,15 @@ class TimersManager

/**
* @brief Executes one ready timer if available
*
*
* @return true if there was a timer ready
*/
bool execute_head_timer();

/**
* @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.
*/
Expand All @@ -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.
Expand All @@ -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.
*/
Expand Down Expand Up @@ -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;
}
}

Expand Down Expand Up @@ -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;
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/src/rclcpp/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"));
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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<void> request = service->create_request();
Expand All @@ -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<void> response = client->create_response();
Expand Down
89 changes: 45 additions & 44 deletions rclcpp/src/rclcpp/executors/events_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <memory>
#include <queue>
#include <string>
#include <utility>

#include "rclcpp/executors/events_executor.hpp"
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -260,7 +261,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) {
Expand Down Expand Up @@ -295,11 +296,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");
Expand Down Expand Up @@ -330,7 +331,7 @@ EventsExecutor::remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify)
}

void
EventsExecutor::consume_all_events(std::queue<ExecutorEvent> &event_queue)
EventsExecutor::consume_all_events(std::queue<ExecutorEvent> & event_queue)
{
while (!event_queue.empty()) {
ExecutorEvent event = event_queue.front();
Expand All @@ -341,43 +342,43 @@ EventsExecutor::consume_all_events(std::queue<ExecutorEvent> &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<rclcpp::SubscriptionBase *>(
static_cast<const rclcpp::SubscriptionBase*>(event.entity));
execute_subscription(subscription);
break;
}

case SERVICE_EVENT:
{
auto service = const_cast<rclcpp::ServiceBase*>(
static_cast<const rclcpp::ServiceBase*>(event.entity));
execute_service(service);
break;
}

case CLIENT_EVENT:
{
auto client = const_cast<rclcpp::ClientBase*>(
static_cast<const rclcpp::ClientBase*>(event.entity));
execute_client(client);
switch (event.type) {
case SUBSCRIPTION_EVENT:
{
auto subscription = const_cast<rclcpp::SubscriptionBase *>(
static_cast<const rclcpp::SubscriptionBase *>(event.entity));
execute_subscription(subscription);
break;
}

case SERVICE_EVENT:
{
auto service = const_cast<rclcpp::ServiceBase *>(
static_cast<const rclcpp::ServiceBase *>(event.entity));
execute_service(service);
break;
}

case CLIENT_EVENT:
{
auto client = const_cast<rclcpp::ClientBase *>(
static_cast<const rclcpp::ClientBase *>(event.entity));
execute_client(client);
break;
}

case WAITABLE_EVENT:
{
auto waitable = const_cast<rclcpp::Waitable *>(
static_cast<const rclcpp::Waitable *>(event.entity));
waitable->execute();
break;
}

default:
throw std::runtime_error("EventsExecutor received unrecognized event");
break;
}

case WAITABLE_EVENT:
{
auto waitable = const_cast<rclcpp::Waitable*>(
static_cast<const rclcpp::Waitable*>(event.entity));
waitable->execute();
break;
}

default:
throw std::runtime_error("EventsExecutor received unrecognized event");
break;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand All @@ -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"));
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executors/timers_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}
12 changes: 6 additions & 6 deletions rclcpp/src/rclcpp/service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"));
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"));
Expand Down
4 changes: 3 additions & 1 deletion rclcpp/src/rclcpp/subscription_intra_process_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <string>

#include "rclcpp/experimental/subscription_intra_process_base.hpp"

using rclcpp::experimental::SubscriptionIntraProcessBase;
Expand Down Expand Up @@ -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"));
}
}
}
7 changes: 4 additions & 3 deletions rclcpp/src/rclcpp/waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
}

0 comments on commit 2037ee5

Please sign in to comment.