forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_timer.cpp
More file actions
152 lines (125 loc) · 4.08 KB
/
test_timer.cpp
File metadata and controls
152 lines (125 loc) · 4.08 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
// 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 <atomic>
#include <chrono>
#include <exception>
#include <memory>
#include "rcl/timer.h"
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals;
/// Timer testing bring up and teardown
class TestTimer : public ::testing::Test
{
protected:
void SetUp() override
{
rclcpp::init(0, nullptr);
executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
has_timer_run.store(false);
cancel_timer.store(false);
test_node = std::make_shared<rclcpp::Node>("test_timer_node");
timer = test_node->create_wall_timer(100ms,
[this]() -> void
{
this->has_timer_run.store(true);
if (this->cancel_timer.load()) {
this->timer->cancel();
}
// prevent any tests running timer from blocking
this->executor->cancel();
}
);
executor->add_node(test_node);
// don't start spinning, let the test dictate when
}
void TearDown() override
{
timer.reset();
test_node.reset();
executor.reset();
rclcpp::shutdown();
}
// set to true if the timer callback executed, false otherwise
std::atomic<bool> has_timer_run;
// flag used to cancel the timer in the timer callback. If true cancel the timer, otherwise
// cancel the executor (preventing any tests from blocking)
std::atomic<bool> cancel_timer;
rclcpp::Node::SharedPtr test_node;
std::shared_ptr<rclcpp::TimerBase> timer;
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor;
};
/// check if initial states are set as expected
void test_initial_conditions(
std::shared_ptr<rclcpp::TimerBase> & timer,
std::atomic<bool> & has_timer_run)
{
ASSERT_FALSE(timer->is_canceled());
ASSERT_FALSE(has_timer_run.load());
}
/// Simple test
TEST_F(TestTimer, test_simple_cancel)
{
// expect clean state, don't run otherwise
test_initial_conditions(timer, has_timer_run);
// cancel
timer->cancel();
EXPECT_TRUE(timer->is_canceled());
EXPECT_FALSE(has_timer_run.load());
}
/// Test state when using reset
TEST_F(TestTimer, test_is_canceled_reset)
{
// expect clean state, don't run otherwise
test_initial_conditions(timer, has_timer_run);
// reset shouldn't affect state (not canceled yet)
timer->reset();
EXPECT_FALSE(timer->is_canceled());
// cancel after reset
timer->cancel();
EXPECT_TRUE(timer->is_canceled());
// reset and cancel
timer->reset();
EXPECT_FALSE(timer->is_canceled());
timer->cancel();
EXPECT_TRUE(timer->is_canceled());
EXPECT_FALSE(has_timer_run.load());
}
/// Run and check state, cancel the executor
TEST_F(TestTimer, test_run_cancel_executor)
{
// expect clean state, don't run otherwise
test_initial_conditions(timer, has_timer_run);
// run the timer (once, this forces an executor cancel so spin won't block)
// but the timer was not explicitly cancelled
executor->spin();
EXPECT_TRUE(has_timer_run.load());
// force a timer cancel
EXPECT_FALSE(timer->is_canceled());
timer->cancel();
EXPECT_TRUE(timer->is_canceled());
}
/// Run and check state, cancel the timer
TEST_F(TestTimer, test_run_cancel_timer)
{
// expect clean state, don't run otherwise
test_initial_conditions(timer, has_timer_run);
// force a timer cancellation
cancel_timer.store(true);
// run the timer (once, this forces an executor cancel so spin won't block)
executor->spin();
EXPECT_TRUE(has_timer_run.load());
EXPECT_TRUE(timer->is_canceled());
}