Skip to content

Commit

Permalink
Additional checking around the timer.
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll committed Mar 28, 2018
1 parent ace16b7 commit 1488317
Show file tree
Hide file tree
Showing 3 changed files with 35 additions and 18 deletions.
11 changes: 10 additions & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -329,6 +329,7 @@ if(BUILD_TESTING)
ament_target_dependencies(test_utilities
"rcl")
target_link_libraries(test_utilities ${PROJECT_NAME})
endif()

ament_add_gtest(test_multi_threaded_executor test/executors/test_multi_threaded_executor.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
Expand All @@ -337,7 +338,15 @@ if(BUILD_TESTING)
"rcl")
target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME})
endif()
endif()

ament_add_gtest(test_single_threaded_executor test/executors/test_single_threaded_executor.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
if(TARGET test_single_threaded_executor)
ament_target_dependencies(test_single_threaded_executor
"rcl")
target_link_libraries(test_single_threaded_executor ${PROJECT_NAME})
endif()
endif(BUILD_TESTING)

ament_package(
CONFIG_EXTRAS rclcpp-extras.cmake
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <iostream>
#include <list>
#include <memory>
#include <set>
#include <string>
#include <vector>

Expand Down Expand Up @@ -351,6 +352,7 @@ class Executor
RCLCPP_DISABLE_COPY(Executor)

std::vector<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> weak_nodes_;
std::set<rclcpp::TimerBase::SharedPtr> taken_timers_;
};

} // namespace executor
Expand Down
40 changes: 23 additions & 17 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,16 +36,16 @@ using rclcpp::executor::ExecutorArgs;
using rclcpp::executor::FutureReturnCode;

Executor::Executor(const ExecutorArgs & args)
: spinning(false),
: spinning(false),
memory_strategy_(args.memory_strategy)
{
rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options();
if (rcl_guard_condition_init(
&interrupt_guard_condition_, guard_condition_options) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Failed to create interrupt guard condition in Executor constructor: ") +
rcl_get_error_string_safe());
std::string("Failed to create interrupt guard condition in Executor constructor: ") +
rcl_get_error_string_safe());
}

// The number of guard conditions is always at least 2: 1 for the ctrl-c guard cond,
Expand Down Expand Up @@ -251,6 +251,10 @@ Executor::execute_any_executable(AnyExecutable::SharedPtr any_exec)
}
if (any_exec->timer) {
execute_timer(any_exec->timer);
auto it = taken_timers_.find(any_exec->timer);
if (it != taken_timers_.end()) {
taken_timers_.erase(it);
}
}
if (any_exec->subscription) {
execute_subscription(any_exec->subscription);
Expand Down Expand Up @@ -281,7 +285,7 @@ Executor::execute_subscription(
rmw_message_info_t message_info;

auto ret = rcl_take(subscription->get_subscription_handle().get(),
message.get(), &message_info);
message.get(), &message_info);
if (ret == RCL_RET_OK) {
message_info.from_intra_process = false;
subscription->handle_message(message, message_info);
Expand Down Expand Up @@ -379,7 +383,7 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
weak_nodes_.erase(
remove_if(
weak_nodes_.begin(), weak_nodes_.end(),
[](rclcpp::node_interfaces::NodeBaseInterface::WeakPtr i)
[] (rclcpp::node_interfaces::NodeBaseInterface::WeakPtr i)
{
return i.expired();
}
Expand Down Expand Up @@ -407,40 +411,40 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
&wait_set_, memory_strategy_->number_of_ready_subscriptions()) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Couldn't resize the number of subscriptions in wait set : ") +
rcl_get_error_string_safe());
std::string("Couldn't resize the number of subscriptions in wait set : ") +
rcl_get_error_string_safe());
}

if (rcl_wait_set_resize_services(
&wait_set_, memory_strategy_->number_of_ready_services()) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Couldn't resize the number of services in wait set : ") +
rcl_get_error_string_safe());
std::string("Couldn't resize the number of services in wait set : ") +
rcl_get_error_string_safe());
}

if (rcl_wait_set_resize_clients(
&wait_set_, memory_strategy_->number_of_ready_clients()) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Couldn't resize the number of clients in wait set : ") +
rcl_get_error_string_safe());
std::string("Couldn't resize the number of clients in wait set : ") +
rcl_get_error_string_safe());
}

if (rcl_wait_set_resize_guard_conditions(
&wait_set_, memory_strategy_->number_of_guard_conditions()) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Couldn't resize the number of guard_conditions in wait set : ") +
rcl_get_error_string_safe());
std::string("Couldn't resize the number of guard_conditions in wait set : ") +
rcl_get_error_string_safe());
}

if (rcl_wait_set_resize_timers(
&wait_set_, memory_strategy_->number_of_ready_timers()) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Couldn't resize the number of timers in wait set : ") +
rcl_get_error_string_safe());
std::string("Couldn't resize the number of timers in wait set : ") +
rcl_get_error_string_safe());
}

if (!memory_strategy_->add_handles_to_wait_set(&wait_set_)) {
Expand Down Expand Up @@ -522,10 +526,12 @@ Executor::get_next_timer(AnyExecutable::SharedPtr any_exec)
}
for (auto & timer_ref : group->get_timer_ptrs()) {
auto timer = timer_ref.lock();
if (timer && timer->is_ready()) {

if (timer && timer->is_ready() && taken_timers_.count(timer) == 0) {
any_exec->timer = timer;
any_exec->callback_group = group;
node = get_node_by_group(group);
taken_timers_.insert(timer);
return;
}
}
Expand Down Expand Up @@ -603,7 +609,7 @@ rclcpp::executor::operator<<(std::ostream & os, const FutureReturnCode & future_
}

std::string
rclcpp::executor::to_string(const FutureReturnCode &future_return_code)
rclcpp::executor::to_string(const FutureReturnCode & future_return_code)
{
using enum_type = std::underlying_type<FutureReturnCode>::type;
std::string prefix = "Unknown enum value (";
Expand Down

0 comments on commit 1488317

Please sign in to comment.