Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add method to read timer cancellation #8

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -397,6 +397,14 @@ if(BUILD_TESTING)
target_link_libraries(test_time ${PROJECT_NAME})
endif()

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

ament_add_gtest(test_time_source test/test_time_source.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}")
if(TARGET test_time_source)
Expand Down
5 changes: 5 additions & 0 deletions rclcpp/include/rclcpp/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,11 @@ class TimerBase
void
cancel();

/// Return the timer cancellation state.
RCLCPP_PUBLIC
bool
is_cancelled();

RCLCPP_PUBLIC
void
reset();
Expand Down
11 changes: 11 additions & 0 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,17 @@ TimerBase::cancel()
}
}

bool
TimerBase::is_cancelled()
{
bool is_canceled = false;
if (rcl_timer_is_canceled(timer_handle_.get(), &is_canceled) != RCL_RET_OK) {
throw std::runtime_error(std::string("Couldn't get timer cancelled state: ") +
rcl_get_error_string().str);
}
return is_canceled;
}

void
TimerBase::reset()
{
Expand Down
67 changes: 67 additions & 0 deletions rclcpp/test/test_timer.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include <chrono>
#include <exception>
#include <memory>

#include "rcl/timer.h"

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

class TestTimer : public ::testing::Test
{
protected:
void SetUp()
{
rclcpp::init(0, nullptr);
test_node = std::make_shared<rclcpp::Node>("test_timer_node");
}

void TearDown()
{
test_node.reset();
rclcpp::shutdown();
}

rclcpp::Node::SharedPtr test_node;
};

TEST_F(TestTimer, test_is_cancelled)
{
try {
auto timer = test_node->create_wall_timer(1s,
[]() -> void {
printf("this is a test\n");
}
);

// start and cancel
ASSERT_FALSE(timer->is_cancelled());
timer->cancel();
ASSERT_TRUE(timer->is_cancelled());

// reset and cancel
timer->reset();
ASSERT_FALSE(timer->is_cancelled());
timer->cancel();
ASSERT_TRUE(timer->is_cancelled());
} catch (std::exception & e) {
FAIL() << e.what();
}
}