Skip to content

Commit

Permalink
Reformat style error throw
Browse files Browse the repository at this point in the history
Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
  • Loading branch information
Blast545 committed Sep 30, 2020
1 parent e36cc76 commit ace8406
Showing 1 changed file with 13 additions and 14 deletions.
27 changes: 13 additions & 14 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,9 @@ TimerBase::~TimerBase()
void
TimerBase::cancel()
{
if (rcl_timer_cancel(timer_handle_.get()) != RCL_RET_OK) {
throw std::runtime_error(std::string("Couldn't cancel timer: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_cancel(timer_handle_.get());
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't cancel timer");
}
}

Expand All @@ -95,17 +96,19 @@ TimerBase::is_canceled()
void
TimerBase::reset()
{
if (rcl_timer_reset(timer_handle_.get()) != RCL_RET_OK) {
throw std::runtime_error(std::string("Couldn't reset timer: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_reset(timer_handle_.get());
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't reset timer");
}
}

bool
TimerBase::is_ready()
{
bool ready = false;
if (rcl_timer_is_ready(timer_handle_.get(), &ready) != RCL_RET_OK) {
throw std::runtime_error(std::string("Failed to check timer: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_is_ready(timer_handle_.get(), &ready);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to check timer");
}
return ready;
}
Expand All @@ -114,14 +117,10 @@ std::chrono::nanoseconds
TimerBase::time_until_trigger()
{
int64_t time_until_next_call = 0;
if (
rcl_timer_get_time_until_next_call(
timer_handle_.get(),
&time_until_next_call) != RCL_RET_OK)
{
throw std::runtime_error(
std::string(
"Timer could not get time until next call: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_get_time_until_next_call(
timer_handle_.get(), &time_until_next_call);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Timer could not get time until next call");
}
return std::chrono::nanoseconds(time_until_next_call);
}
Expand Down

0 comments on commit ace8406

Please sign in to comment.