forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_logging.cpp
More file actions
255 lines (227 loc) · 7.94 KB
/
test_logging.cpp
File metadata and controls
255 lines (227 loc) · 7.94 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
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
// Copyright 2017 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 <gmock/gmock.h>
#include <chrono>
#include <string>
#include <thread>
#include <vector>
#include "rclcpp/clock.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/logging.hpp"
#include "rcutils/logging.h"
#include "rcutils/time.h"
using ::testing::EndsWith;
size_t g_log_calls = 0;
rclcpp::Logger g_logger = rclcpp::get_logger("name");
struct LogEvent
{
const rcutils_log_location_t * location;
int level;
std::string name;
rcutils_time_point_value_t timestamp;
std::string message;
};
LogEvent g_last_log_event;
class TestLoggingMacros : public ::testing::Test
{
public:
rcutils_logging_output_handler_t previous_output_handler;
void SetUp()
{
g_log_calls = 0;
ASSERT_EQ(RCUTILS_RET_OK, rcutils_logging_initialize());
rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_DEBUG);
auto rcutils_logging_console_output_handler = [](
const rcutils_log_location_t * location,
int level, const char * name, rcutils_time_point_value_t timestamp,
const char * format, va_list * args) -> void
{
g_log_calls += 1;
g_last_log_event.location = location;
g_last_log_event.level = level;
g_last_log_event.name = name ? name : "";
g_last_log_event.timestamp = timestamp;
char buffer[1024];
vsnprintf(buffer, sizeof(buffer), format, *args);
g_last_log_event.message = buffer;
};
this->previous_output_handler = rcutils_logging_get_output_handler();
rcutils_logging_set_output_handler(rcutils_logging_console_output_handler);
}
void TearDown()
{
rcutils_logging_set_output_handler(this->previous_output_handler);
ASSERT_EQ(RCUTILS_RET_OK, rcutils_logging_shutdown());
EXPECT_FALSE(g_rcutils_logging_initialized);
}
};
class DummyNode
{
public:
DummyNode()
{
clock_ = rclcpp::Clock::make_shared(RCL_ROS_TIME);
}
rclcpp::Clock::SharedPtr get_clock()
{
return clock_;
}
private:
rclcpp::Clock::SharedPtr clock_;
};
TEST_F(TestLoggingMacros, test_logging_named) {
for (int i : {1, 2, 3}) {
RCLCPP_DEBUG(g_logger, "message %d", i);
}
size_t expected_location = __LINE__ - 2u;
EXPECT_EQ(3u, g_log_calls);
EXPECT_TRUE(g_last_log_event.location != NULL);
if (g_last_log_event.location) {
EXPECT_STREQ("TestBody", g_last_log_event.location->function_name);
EXPECT_THAT(g_last_log_event.location->file_name, EndsWith("test_logging.cpp"));
EXPECT_EQ(expected_location, g_last_log_event.location->line_number);
}
EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
EXPECT_EQ("message 3", g_last_log_event.message);
}
TEST_F(TestLoggingMacros, test_logging_stream) {
for (std::string i : {"one", "two", "three"}) {
RCLCPP_DEBUG_STREAM(g_logger, "message " << i);
}
EXPECT_EQ(3u, g_log_calls);
EXPECT_EQ("message three", g_last_log_event.message);
RCLCPP_DEBUG_STREAM(g_logger, 4 << "th message");
EXPECT_EQ("4th message", g_last_log_event.message);
RCLCPP_DEBUG_STREAM(g_logger, "message " << 5);
EXPECT_EQ("message 5", g_last_log_event.message);
}
TEST_F(TestLoggingMacros, test_logging_once) {
for (int i : {1, 2, 3}) {
RCLCPP_INFO_ONCE(g_logger, "message %d", i);
}
EXPECT_EQ(1u, g_log_calls);
EXPECT_EQ(RCUTILS_LOG_SEVERITY_INFO, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
EXPECT_EQ("message 1", g_last_log_event.message);
// Check that another instance has a context that's independent to the call above's
g_log_calls = 0;
for (int i : {1, 2, 3}) {
RCLCPP_INFO_ONCE(g_logger, "second message %d", i);
}
EXPECT_EQ(1u, g_log_calls);
EXPECT_EQ(RCUTILS_LOG_SEVERITY_INFO, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
EXPECT_EQ("second message 1", g_last_log_event.message);
}
TEST_F(TestLoggingMacros, test_logging_expression) {
for (int i : {1, 2, 3, 4, 5, 6}) {
RCLCPP_INFO_EXPRESSION(g_logger, i % 3, "message %d", i);
}
EXPECT_EQ(4u, g_log_calls);
EXPECT_EQ("message 5", g_last_log_event.message);
}
int g_counter = 0;
bool mod3()
{
return (g_counter % 3) != 0;
}
TEST_F(TestLoggingMacros, test_logging_function) {
for (int i : {1, 2, 3, 4, 5, 6}) {
g_counter = i;
RCLCPP_INFO_FUNCTION(g_logger, &mod3, "message %d", i);
}
EXPECT_EQ(4u, g_log_calls);
EXPECT_EQ("message 5", g_last_log_event.message);
}
TEST_F(TestLoggingMacros, test_logging_skipfirst) {
for (uint32_t i : {1, 2, 3, 4, 5}) {
RCLCPP_WARN_SKIPFIRST(g_logger, "message %u", i);
EXPECT_EQ(i - 1, g_log_calls);
}
}
TEST_F(TestLoggingMacros, test_throttle) {
using namespace std::chrono_literals;
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
for (uint64_t i = 0; i < 3; ++i) {
RCLCPP_DEBUG_THROTTLE(g_logger, steady_clock, 10000, "Throttling");
}
EXPECT_EQ(1u, g_log_calls);
RCLCPP_DEBUG_SKIPFIRST_THROTTLE(g_logger, steady_clock, 1, "Skip first throttling");
EXPECT_EQ(1u, g_log_calls);
for (uint64_t i = 0; i < 6; ++i) {
RCLCPP_DEBUG_THROTTLE(g_logger, steady_clock, 100, "Throttling");
RCLCPP_DEBUG_SKIPFIRST_THROTTLE(g_logger, steady_clock, 400, "Throttling");
std::this_thread::sleep_for(50ms);
}
EXPECT_EQ(4u, g_log_calls);
rclcpp::Clock ros_clock(RCL_ROS_TIME);
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(ros_clock.get_clock_handle()));
RCLCPP_DEBUG_THROTTLE(g_logger, ros_clock, 10000, "Throttling");
rcl_clock_t * clock = ros_clock.get_clock_handle();
ASSERT_TRUE(clock);
EXPECT_EQ(4u, g_log_calls);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock, RCUTILS_MS_TO_NS(10)));
for (uint64_t i = 0; i < 2; ++i) {
RCLCPP_DEBUG_THROTTLE(g_logger, ros_clock, 10, "Throttling");
if (i == 0) {
EXPECT_EQ(5u, g_log_calls);
rcl_time_point_value_t clock_ns = ros_clock.now().nanoseconds() + RCUTILS_MS_TO_NS(10);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock, clock_ns));
} else {
EXPECT_EQ(6u, g_log_calls);
}
}
DummyNode node;
rcl_clock_t * node_clock = node.get_clock()->get_clock_handle();
ASSERT_TRUE(node_clock);
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(node_clock));
EXPECT_EQ(6u, g_log_calls);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(node_clock, RCUTILS_MS_TO_NS(10)));
for (uint64_t i = 0; i < 3; ++i) {
RCLCPP_DEBUG_THROTTLE(g_logger, *node.get_clock(), 10, "Throttling");
if (i == 0) {
EXPECT_EQ(7u, g_log_calls);
rcl_time_point_value_t clock_ns = node.get_clock()->now().nanoseconds() + RCUTILS_MS_TO_NS(5);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(node_clock, clock_ns));
} else if (i == 1) {
EXPECT_EQ(7u, g_log_calls);
rcl_time_point_value_t clock_ns = node.get_clock()->now().nanoseconds() + RCUTILS_MS_TO_NS(5);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(node_clock, clock_ns));
} else {
EXPECT_EQ(8u, g_log_calls);
}
}
}
bool log_function(rclcpp::Logger logger)
{
RCLCPP_INFO(logger, "successful log");
return true;
}
bool log_function_const(const rclcpp::Logger logger)
{
RCLCPP_INFO(logger, "successful log");
return true;
}
bool log_function_const_ref(const rclcpp::Logger & logger)
{
RCLCPP_INFO(logger, "successful log");
return true;
}
TEST_F(TestLoggingMacros, test_log_from_node) {
auto logger = rclcpp::get_logger("test_logging_logger");
EXPECT_TRUE(log_function(logger));
EXPECT_TRUE(log_function_const(logger));
EXPECT_TRUE(log_function_const_ref(logger));
}