Skip to content

Commit

Permalink
Throw exception if rcl_timer_init fails (#1179)
Browse files Browse the repository at this point in the history
* Throw exception if rcl_timer_init fails

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

* Add bad-argument tests for GenericTimer

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

* Add comments

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

* Address feedback

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

* Address feedback

Signed-off-by: Stephen Brawner <brawner@gmail.com>
  • Loading branch information
brawner committed Oct 19, 2020
1 parent f71d3bf commit 823e1dd
Show file tree
Hide file tree
Showing 2 changed files with 45 additions and 9 deletions.
14 changes: 5 additions & 9 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,15 +61,11 @@ TimerBase::TimerBase(
rcl_clock_t * clock_handle = clock_->get_clock_handle();
{
std::lock_guard<std::mutex> clock_guard(clock_->get_clock_mutex());
if (
rcl_timer_init(
timer_handle_.get(), clock_handle, rcl_context.get(), period.count(), nullptr,
rcl_get_default_allocator()) != RCL_RET_OK)
{
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Couldn't initialize rcl timer handle: %s\n", rcl_get_error_string().str);
rcl_reset_error();
rcl_ret_t ret = rcl_timer_init(
timer_handle_.get(), clock_handle, rcl_context.get(), period.count(), nullptr,
rcl_get_default_allocator());
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't initialize rcl timer handle");
}
}
}
Expand Down
40 changes: 40 additions & 0 deletions rclcpp/test/rclcpp/test_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <chrono>
#include <exception>
#include <memory>
#include <utility>

#include "rcl/timer.h"

Expand Down Expand Up @@ -151,3 +152,42 @@ TEST_F(TestTimer, test_run_cancel_timer)
EXPECT_TRUE(has_timer_run.load());
EXPECT_TRUE(timer->is_canceled());
}

TEST_F(TestTimer, test_bad_arguments) {
auto node_base = rclcpp::node_interfaces::get_node_base_interface(test_node);
auto context = node_base->get_context();

auto steady_clock = std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME);

// Negative period
EXPECT_THROW(
rclcpp::GenericTimer<void (*)()>(steady_clock, -1ms, []() {}, context),
rclcpp::exceptions::RCLInvalidArgument);

// Very negative period
constexpr auto nanoseconds_min = std::chrono::nanoseconds::min();
EXPECT_THROW(
rclcpp::GenericTimer<void (*)()>(
steady_clock, nanoseconds_min, []() {}, context),
rclcpp::exceptions::RCLInvalidArgument);

// nanoseconds max, should be ok
constexpr auto nanoseconds_max = std::chrono::nanoseconds::max();
EXPECT_NO_THROW(
rclcpp::GenericTimer<void (*)()>(
steady_clock, nanoseconds_max, []() {}, context));

// 0 duration period, should be ok
EXPECT_NO_THROW(
rclcpp::GenericTimer<void (*)()>(steady_clock, 0ms, []() {}, context));

// context is null, which resorts to default
EXPECT_NO_THROW(
rclcpp::GenericTimer<void (*)()>(steady_clock, 1ms, []() {}, nullptr));

// Clock is unitialized
auto unitialized_clock = std::make_shared<rclcpp::Clock>(RCL_CLOCK_UNINITIALIZED);
EXPECT_THROW(
rclcpp::GenericTimer<void (*)()>(unitialized_clock, 1us, []() {}, context),
rclcpp::exceptions::RCLError);
}

0 comments on commit 823e1dd

Please sign in to comment.