forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_create_timer.cpp
More file actions
118 lines (98 loc) · 3.53 KB
/
test_create_timer.cpp
File metadata and controls
118 lines (98 loc) · 3.53 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
// 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 <memory>
#include "node_interfaces/node_wrapper.hpp"
#include "rclcpp/create_timer.hpp"
#include "rclcpp/executors.hpp"
#include "rclcpp/node.hpp"
using namespace std::chrono_literals;
TEST(TestCreateTimer, timer_executes)
{
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("test_create_timer_node");
std::atomic<bool> got_callback{false};
rclcpp::TimerBase::SharedPtr timer;
timer = rclcpp::create_timer(
node,
node->get_clock(),
rclcpp::Duration(0ms),
[&got_callback, &timer]() {
got_callback = true;
timer->cancel();
});
rclcpp::spin_some(node);
ASSERT_TRUE(got_callback);
rclcpp::shutdown();
}
TEST(TestCreateTimer, call_with_node_wrapper_compiles)
{
rclcpp::init(0, nullptr);
NodeWrapper node("test_create_timer_call_with_node_wrapper_compiles");
rclcpp::TimerBase::SharedPtr timer;
timer = rclcpp::create_timer(
node,
node.get_node_clock_interface()->get_clock(),
rclcpp::Duration(0ms),
[]() {});
rclcpp::shutdown();
}
TEST(TestCreateTimer, call_wall_timer_with_bad_arguments)
{
rclcpp::init(0, nullptr);
NodeWrapper node("test_create_wall_timers_with_bad_arguments");
auto callback = []() {};
rclcpp::CallbackGroup::SharedPtr group = nullptr;
auto node_interface =
rclcpp::node_interfaces::get_node_base_interface(node).get();
auto timers_interface =
rclcpp::node_interfaces::get_node_timers_interface(node).get();
// Negative period
EXPECT_THROW(
rclcpp::create_wall_timer(-1ms, callback, group, node_interface, timers_interface),
std::invalid_argument);
// Very negative period
constexpr auto nanoseconds_min = std::chrono::nanoseconds::min();
EXPECT_THROW(
rclcpp::create_wall_timer(
nanoseconds_min, callback, group, node_interface, timers_interface),
std::invalid_argument);
// Period must be less than nanoseconds::max()
constexpr auto nanoseconds_max = std::chrono::nanoseconds::min();
EXPECT_THROW(
rclcpp::create_wall_timer(
nanoseconds_max, callback, group, node_interface, timers_interface),
std::invalid_argument);
EXPECT_NO_THROW(
rclcpp::create_wall_timer(
nanoseconds_max - 1us, callback, group, node_interface, timers_interface));
EXPECT_NO_THROW(
rclcpp::create_wall_timer(0ms, callback, group, node_interface, timers_interface));
// Period must be less than nanoseconds::max()
constexpr auto hours_max = std::chrono::hours::max();
EXPECT_THROW(
rclcpp::create_wall_timer(hours_max, callback, group, node_interface, timers_interface),
std::invalid_argument);
// node_interface is null
EXPECT_THROW(
rclcpp::create_wall_timer(1ms, callback, group, nullptr, timers_interface),
std::invalid_argument);
// timers_interface is null
EXPECT_THROW(
rclcpp::create_wall_timer(1ms, callback, group, node_interface, nullptr),
std::invalid_argument);
rclcpp::shutdown();
}