Skip to content

Commit

Permalink
[foxy backport] Add executor unit tests #1336 (#1395)
Browse files Browse the repository at this point in the history
* Improve the error messages in the Executor class.

In particular, make sure to use 'throw_from_rcl_error'
as much as possible.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Allow mimick patching of methods with up to 9 arguments.

This will be needed by the executor tests.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Add in unit tests for the Executor class.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Adjust test_executor for foxy

Signed-off-by: Stephen Brawner <brawner@gmail.com>

Co-authored-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
brawner and clalancette authored Oct 9, 2020
1 parent 9e59de0 commit 44b8bf4
Show file tree
Hide file tree
Showing 4 changed files with 400 additions and 11 deletions.
22 changes: 12 additions & 10 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ Executor::Executor(const rclcpp::ExecutorOptions & options)
"failed to destroy guard condition: %s", rcl_get_error_string().str);
rcl_reset_error();
}
throw std::runtime_error("Failed to create wait set in Executor constructor");
throw_from_rcl_error(ret, "Failed to create wait set in Executor constructor");
}
}

Expand Down Expand Up @@ -279,8 +279,9 @@ void
Executor::cancel()
{
spinning.store(false);
if (rcl_trigger_guard_condition(&interrupt_guard_condition_) != RCL_RET_OK) {
throw std::runtime_error(rcl_get_error_string().str);
rcl_ret_t ret = rcl_trigger_guard_condition(&interrupt_guard_condition_);
if (ret != RCL_RET_OK) {
throw_from_rcl_error(ret, "Failed to trigger guard condition in cancel");
}
}

Expand Down Expand Up @@ -318,8 +319,9 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
any_exec.callback_group->can_be_taken_from().store(true);
// Wake the wait, because it may need to be recalculated or work that
// was previously blocked is now available.
if (rcl_trigger_guard_condition(&interrupt_guard_condition_) != RCL_RET_OK) {
throw std::runtime_error(rcl_get_error_string().str);
rcl_ret_t ret = rcl_trigger_guard_condition(&interrupt_guard_condition_);
if (ret != RCL_RET_OK) {
throw_from_rcl_error(ret, "Failed to trigger guard condition from execute_any_executable");
}
}

Expand Down Expand Up @@ -484,19 +486,19 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
}
}
// clear wait set
if (rcl_wait_set_clear(&wait_set_) != RCL_RET_OK) {
throw std::runtime_error("Couldn't clear wait set");
rcl_ret_t ret = rcl_wait_set_clear(&wait_set_);
if (ret != RCL_RET_OK) {
throw_from_rcl_error(ret, "Couldn't clear wait set");
}

// The size of waitables are accounted for in size of the other entities
rcl_ret_t ret = rcl_wait_set_resize(
ret = rcl_wait_set_resize(
&wait_set_, memory_strategy_->number_of_ready_subscriptions(),
memory_strategy_->number_of_guard_conditions(), memory_strategy_->number_of_ready_timers(),
memory_strategy_->number_of_ready_clients(), memory_strategy_->number_of_ready_services(),
memory_strategy_->number_of_ready_events());
if (RCL_RET_OK != ret) {
throw std::runtime_error(
std::string("Couldn't resize the wait set : ") + rcl_get_error_string().str);
throw_from_rcl_error(ret, "Couldn't resize the wait set");
}

if (!memory_strategy_->add_handles_to_wait_set(&wait_set_)) {
Expand Down
8 changes: 8 additions & 0 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -622,6 +622,14 @@ if(TARGET test_rclcpp_gtest_macros)
target_link_libraries(test_rclcpp_gtest_macros ${PROJECT_NAME})
endif()

ament_add_gtest(test_executor rclcpp/test_executor.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}"
)
if(TARGET test_executor)
ament_target_dependencies(test_executor "rcl")
target_link_libraries(test_executor ${PROJECT_NAME} mimick)
endif()

# Install test resources
install(
DIRECTORY resources
Expand Down
58 changes: 57 additions & 1 deletion rclcpp/test/mocking_utils/patch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,7 @@ struct PatchTraits<ID, void(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5)>
mock_type, void, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5);
};

/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5)
/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6)
/// free functions.
/**
* \tparam ID Numerical identifier of the patch. Ought to be unique.
Expand All @@ -270,6 +270,62 @@ struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6)>
mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6);
};

/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7)
/// free functions.
/**
* \tparam ID Numerical identifier of the patch. Ought to be unique.
* \tparam ReturnT Return value type.
* \tparam ArgTx Argument types.
*/
template<size_t ID, typename ReturnT,
typename ArgT0, typename ArgT1,
typename ArgT2, typename ArgT3,
typename ArgT4, typename ArgT5,
typename ArgT6, typename ArgT7>
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7)>
{
mmk_mock_define(
mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7);
};

/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7, ArgT8)
/// free functions.
/**
* \tparam ID Numerical identifier of the patch. Ought to be unique.
* \tparam ReturnT Return value type.
* \tparam ArgTx Argument types.
*/
template<size_t ID, typename ReturnT,
typename ArgT0, typename ArgT1,
typename ArgT2, typename ArgT3,
typename ArgT4, typename ArgT5,
typename ArgT6, typename ArgT7, typename ArgT8>
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7, ArgT8)>
{
mmk_mock_define(
mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7, ArgT8);
};

/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7,
/// ArgT8, ArgT9) free functions.
/**
* \tparam ID Numerical identifier of the patch. Ought to be unique.
* \tparam ReturnT Return value type.
* \tparam ArgTx Argument types.
*/
template<size_t ID, typename ReturnT,
typename ArgT0, typename ArgT1,
typename ArgT2, typename ArgT3,
typename ArgT4, typename ArgT5,
typename ArgT6, typename ArgT7,
typename ArgT8, typename ArgT9>
struct PatchTraits<ID, ReturnT(
ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7, ArgT8, ArgT9)>
{
mmk_mock_define(
mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6, ArgT7, ArgT8, ArgT9);
};

/// Generic trampoline to wrap generalized callables in plain functions.
/**
* \tparam ID Numerical identifier of this trampoline. Ought to be unique.
Expand Down
Loading

0 comments on commit 44b8bf4

Please sign in to comment.