Skip to content

Commit

Permalink
add timer cancel tests
Browse files Browse the repository at this point in the history
Signed-off-by: Matt Condino <mwcondino@gmail.com>
  • Loading branch information
mwcondino committed Nov 29, 2023
1 parent 811af4b commit 77204eb
Show file tree
Hide file tree
Showing 2 changed files with 150 additions and 0 deletions.
102 changes: 102 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -818,3 +818,105 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
executor.spin();
EXPECT_EQ(kNumMessages, this->callback_count.load());
}

class TimerNode : public rclcpp::Node {
public:
TimerNode(std::string subname)
: Node("timer_node", subname) {


timer1_ = rclcpp::create_timer(this->get_node_base_interface(), get_node_timers_interface(),
get_clock(), 1ms,
std::bind(&TimerNode::Timer1Callback, this));

timer2_ =
rclcpp::create_timer(this->get_node_base_interface(), get_node_timers_interface(),
get_clock(), 1ms,
std::bind(&TimerNode::Timer2Callback, this));
}

int GetTimer1Cnt() { return cnt1_; }
int GetTimer2Cnt() { return cnt2_; }
private:
void Timer1Callback() {
RCLCPP_DEBUG(this->get_logger(), "Timer 1!");
if (++cnt1_ > 5) {
RCLCPP_DEBUG(this->get_logger(), "Timer cancelling itself!");
timer1_->cancel();
}
}

void Timer2Callback() {
RCLCPP_DEBUG(this->get_logger(), "Timer 2!");
cnt2_++;
}

rclcpp::TimerBase::SharedPtr timer1_;
rclcpp::TimerBase::SharedPtr timer2_;
int cnt1_ = 0;
int cnt2_ = 0;
};


template<typename T>
class TestTimerCancelBehavior : public ::testing::Test
{
public:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}

static void TearDownTestCase()
{
rclcpp::shutdown();
}

void SetUp()
{
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
std::stringstream test_name;
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<TimerNode>(test_name.str());
}

void TearDown()
{
node.reset();
}


std::shared_ptr<TimerNode> node;
};

TYPED_TEST_SUITE(TestTimerCancelBehavior, ExecutorTypes, ExecutorTypeNames);

TYPED_TEST(TestTimerCancelBehavior, testOneTimerCancelledWithExecutorSpin) {
// Validate that cancelling one timer yields no change in behavior for other
// timers. Specifically, this tests the behavior when using spin() to run the
// executor, which is the most common usecase.

// Spin the executor in a standalone thread
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
std::thread real_time_thread([&executor]() {
executor.spin();
});

// Cancel to stop the spin after some time.
std::this_thread::sleep_for(15ms);
executor.cancel();

size_t t1_runs = this->node->GetTimer1Cnt();
size_t t2_runs = this->node->GetTimer2Cnt();
EXPECT_NE(t1_runs, t2_runs);
// Check that t2 has significantly more calls
EXPECT_LT(t1_runs + 5, t2_runs);

// Clean up thread object
if (real_time_thread.joinable()) {
real_time_thread.join();
}
}

48 changes: 48 additions & 0 deletions rclcpp/test/rclcpp/test_timers_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@

#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/experimental/timers_manager.hpp"
#include "rclcpp/node.hpp"
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>

using namespace std::chrono_literals;

Expand Down Expand Up @@ -359,3 +361,49 @@ TEST_F(TestTimersManager, infinite_loop)
EXPECT_LT(0u, t1_runs);
EXPECT_LT(0u, t2_runs);
}

// Validate that cancelling one timer yields no change in behavior for other
// timers.
TEST_F(TestTimersManager, check_one_timer_cancel_doesnt_affect_other_timers)
{
auto timers_manager = std::make_shared<TimersManager>(
rclcpp::contexts::get_global_default_context());

size_t t1_runs = 0;
std::shared_ptr<TimerT> t1;
// After a while cancel t1. Don't remove it though.
// Simulates typical usage in a Node where a timer is cancelled but not removed,
// since typical users aren't going to mess around with the timer manager.
t1 = TimerT::make_shared(
1ms,
[&t1_runs, &t1]() {
t1_runs++;
if (t1_runs == 5) {
t1->cancel();
}
},
rclcpp::contexts::get_global_default_context());

size_t t2_runs = 0;
auto t2 = TimerT::make_shared(
1ms,
[&t2_runs]() {
t2_runs++;
},
rclcpp::contexts::get_global_default_context());

// Add timers
timers_manager->add_timer(t1);
timers_manager->add_timer(t2);

// Start timers thread
timers_manager->start();

std::this_thread::sleep_for(15ms);

// t1 has stopped running
EXPECT_NE(t1_runs, t2_runs);
// Check that t2 has significantly more calls
EXPECT_LT(t1_runs + 5, t2_runs);
timers_manager->stop();
}

0 comments on commit 77204eb

Please sign in to comment.