Skip to content

Commit

Permalink
Clear members for StaticExecutorEntitiesCollector to avoid shared_ptr…
Browse files Browse the repository at this point in the history
… dependency

Signed-off-by: Chen Lihui <Lihui.Chen@sony.com>
  • Loading branch information
Chen Lihui authored and Chen Lihui committed Sep 11, 2020
1 parent d66cd96 commit cbf3359
Show file tree
Hide file tree
Showing 5 changed files with 32 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,14 @@ class StaticExecutorEntitiesCollector final
void
init(
rcl_wait_set_t * p_wait_set,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr & memory_strategy,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy,
rcl_guard_condition_t * executor_guard_condition);

/// Finalize StaticExecutorEntitiesCollector to clear resources
RCLCPP_PUBLIC
void
fini();

RCLCPP_PUBLIC
void
execute() override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,14 +194,16 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor

entities_collector_->init(&wait_set_, memory_strategy_, &interrupt_guard_condition_);

rclcpp::FutureReturnCode ret = rclcpp::FutureReturnCode::INTERRUPTED;
while (rclcpp::ok(this->context_)) {
// Do one set of work.
entities_collector_->refresh_wait_set(timeout_left);
execute_ready_executables();
// Check if the future is set, return SUCCESS if it is.
status = future.wait_for(std::chrono::seconds(0));
if (status == std::future_status::ready) {
return rclcpp::FutureReturnCode::SUCCESS;
ret = rclcpp::FutureReturnCode::SUCCESS;
break;
}
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
if (timeout_ns < std::chrono::nanoseconds::zero()) {
Expand All @@ -210,14 +212,17 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor
// Otherwise check if we still have time to wait, return TIMEOUT if not.
auto now = std::chrono::steady_clock::now();
if (now >= end_time) {
return rclcpp::FutureReturnCode::TIMEOUT;
ret = rclcpp::FutureReturnCode::TIMEOUT;
break;
}
// Subtract the elapsed time from the original timeout.
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
}

entities_collector_->fini();

// The future did not complete before ok() returned false, return INTERRUPTED.
return rclcpp::FutureReturnCode::INTERRUPTED;
return ret;
}

/// Not yet implemented, see https://github.com/ros2/rclcpp/issues/1219 for tracking
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ StaticExecutorEntitiesCollector::~StaticExecutorEntitiesCollector()
void
StaticExecutorEntitiesCollector::init(
rcl_wait_set_t * p_wait_set,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr & memory_strategy,
rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy,
rcl_guard_condition_t * executor_guard_condition)
{
// Empty initialize executable list
Expand All @@ -80,6 +80,13 @@ StaticExecutorEntitiesCollector::init(
execute();
}

void
StaticExecutorEntitiesCollector::fini()
{
memory_strategy_->clear_handles();
exec_list_.clear();
}

void
StaticExecutorEntitiesCollector::execute()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@ StaticSingleThreadedExecutor::spin()
entities_collector_->refresh_wait_set();
execute_ready_executables();
}

entities_collector_->fini();
}

void
Expand Down
8 changes: 8 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -410,6 +410,14 @@ class TestWaitable : public rclcpp::Waitable
}
}

~TestWaitable()
{
rcl_ret_t ret = rcl_guard_condition_fini(&gc_);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}

bool
add_to_wait_set(rcl_wait_set_t * wait_set) override
{
Expand Down

0 comments on commit cbf3359

Please sign in to comment.