@@ -7,3 +7,252 @@ This package contains many common functions used by other packages, so please re
7
7
## For developers
8
8
9
9
` autoware_universe_utils.hpp ` header file was removed because the source files that directly/indirectly include this file took a long time for preprocessing.
10
+
11
+ ## ` autoware::universe_utils `
12
+
13
+ ### ` systems `
14
+
15
+ #### ` autoware::universe_utils::TimeKeeper `
16
+
17
+ ##### Constructor
18
+
19
+ ``` cpp
20
+ template <typename ... Reporters>
21
+ explicit TimeKeeper (Reporters... reporters);
22
+ ```
23
+
24
+ - Initializes the `TimeKeeper` with a list of reporters.
25
+
26
+ ##### Methods
27
+
28
+ - `void add_reporter(std::ostream * os);`
29
+
30
+ - Adds a reporter to output processing times to an `ostream`.
31
+ - `os`: Pointer to the `ostream` object.
32
+
33
+ - `void add_reporter(rclcpp::Publisher<ProcessingTimeDetail>::SharedPtr publisher);`
34
+
35
+ - Adds a reporter to publish processing times to an `rclcpp` publisher.
36
+ - `publisher`: Shared pointer to the `rclcpp` publisher.
37
+
38
+ - `void add_reporter(rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher);`
39
+
40
+ - Adds a reporter to publish processing times to an `rclcpp` publisher with `std_msgs::msg::String`.
41
+ - `publisher`: Shared pointer to the `rclcpp` publisher.
42
+
43
+ - `void start_track(const std::string & func_name);`
44
+
45
+ - Starts tracking the processing time of a function.
46
+ - `func_name`: Name of the function to be tracked.
47
+
48
+ - `void end_track(const std::string & func_name);`
49
+ - Ends tracking the processing time of a function.
50
+ - `func_name`: Name of the function to end tracking.
51
+
52
+ ##### Example
53
+
54
+ ```cpp
55
+ #include "autoware/universe_utils/system/time_keeper.hpp"
56
+
57
+ #include <rclcpp/rclcpp.hpp>
58
+
59
+ #include <iostream>
60
+ #include <memory>
61
+
62
+ int main(int argc, char ** argv)
63
+ {
64
+ rclcpp::init(argc, argv);
65
+ auto node = std::make_shared<rclcpp::Node>("time_keeper_example");
66
+
67
+ auto time_keeper = std::make_shared<autoware::universe_utils::TimeKeeper>();
68
+
69
+ time_keeper->add_reporter(&std::cout);
70
+
71
+ auto publisher =
72
+ node->create_publisher<autoware::universe_utils::ProcessingTimeDetail>("processing_time", 10);
73
+
74
+ time_keeper->add_reporter(publisher);
75
+
76
+ auto publisher_str = node->create_publisher<std_msgs::msg::String>("processing_time_str", 10);
77
+
78
+ time_keeper->add_reporter(publisher_str);
79
+
80
+ auto funcA = [&time_keeper]() {
81
+ time_keeper->start_track("funcA");
82
+ std::this_thread::sleep_for(std::chrono::seconds(1));
83
+ time_keeper->end_track("funcA");
84
+ };
85
+
86
+ auto funcB = [&time_keeper, &funcA]() {
87
+ time_keeper->start_track("funcB");
88
+ std::this_thread::sleep_for(std::chrono::seconds(2));
89
+ funcA();
90
+ time_keeper->end_track("funcB");
91
+ };
92
+
93
+ auto funcC = [&time_keeper, &funcB]() {
94
+ time_keeper->start_track("funcC");
95
+ std::this_thread::sleep_for(std::chrono::seconds(3));
96
+ funcB();
97
+ time_keeper->end_track("funcC");
98
+ };
99
+
100
+ funcC();
101
+
102
+ rclcpp::spin(node);
103
+ rclcpp::shutdown();
104
+ return 0;
105
+ }
106
+ ```
107
+
108
+ - Output (console)
109
+
110
+ ``` text
111
+ ==========================
112
+ funcC (6000.7ms)
113
+ └── funcB (3000.44ms)
114
+ └── funcA (1000.19ms)
115
+ ```
116
+
117
+ - Output (` ros2 topic echo /processing_time ` )
118
+
119
+ ``` text
120
+ nodes:
121
+ - id: 1
122
+ name: funcC
123
+ processing_time: 6000.659
124
+ parent_id: 0
125
+ - id: 2
126
+ name: funcB
127
+ processing_time: 3000.415
128
+ parent_id: 1
129
+ - id: 3
130
+ name: funcA
131
+ processing_time: 1000.181
132
+ parent_id: 2
133
+ ---
134
+ ```
135
+
136
+ - Output (` ros2 topic echo /processing_time_str --field data ` )
137
+
138
+ ``` text
139
+ funcC (6000.67ms)
140
+ └── funcB (3000.42ms)
141
+ └── funcA (1000.19ms)
142
+
143
+ ---
144
+ ```
145
+
146
+ #### ` autoware::universe_utils::ScopedTimeTrack `
147
+
148
+ ##### Description
149
+
150
+ Class for automatically tracking the processing time of a function within a scope.
151
+
152
+ ##### Constructor
153
+
154
+ ``` cpp
155
+ ScopedTimeTrack (const std::string & func_name, TimeKeeper & time_keeper);
156
+ ```
157
+
158
+ - `func_name`: Name of the function to be tracked.
159
+ - `time_keeper`: Reference to the `TimeKeeper` object.
160
+
161
+ ##### Destructor
162
+
163
+ ```cpp
164
+ ~ScopedTimeTrack();
165
+ ```
166
+
167
+ - Destroys the ` ScopedTimeTrack ` object, ending the tracking of the function.
168
+
169
+ ##### Example
170
+
171
+ ``` cpp
172
+ #include " autoware/universe_utils/system/time_keeper.hpp"
173
+
174
+ #include < rclcpp/rclcpp.hpp>
175
+
176
+ #include < iostream>
177
+ #include < memory>
178
+
179
+ int main (int argc, char ** argv)
180
+ {
181
+ rclcpp::init(argc, argv);
182
+ auto node = std::make_shared< rclcpp::Node > ("scoped_time_track_example");
183
+
184
+ auto time_keeper = std::make_shared< autoware::universe_utils::TimeKeeper > ();
185
+
186
+ time_keeper->add_reporter(&std::cout);
187
+
188
+ auto publisher =
189
+ node->create_publisher< autoware::universe_utils::ProcessingTimeDetail > ("processing_time", 10);
190
+
191
+ time_keeper->add_reporter(publisher);
192
+
193
+ auto publisher_str = node->create_publisher<std_msgs::msg::String>("processing_time_str", 10);
194
+
195
+ time_keeper->add_reporter(publisher_str);
196
+
197
+ auto funcA = [ &time_keeper] ( ) {
198
+ autoware::universe_utils::ScopedTimeTrack st("funcA", * time_keeper);
199
+ std::this_thread::sleep_for(std::chrono::seconds(1));
200
+ };
201
+
202
+ auto funcB = [ &time_keeper, &funcA] ( ) {
203
+ autoware::universe_utils::ScopedTimeTrack st("funcB", * time_keeper);
204
+ std::this_thread::sleep_for(std::chrono::seconds(2));
205
+ funcA();
206
+ };
207
+
208
+ auto funcC = [ &time_keeper, &funcB] ( ) {
209
+ autoware::universe_utils::ScopedTimeTrack st("funcC", * time_keeper);
210
+ std::this_thread::sleep_for(std::chrono::seconds(3));
211
+ funcB();
212
+ };
213
+
214
+ funcC();
215
+
216
+ rclcpp::spin(node);
217
+ rclcpp::shutdown();
218
+ return 0;
219
+ }
220
+ ```
221
+
222
+ - Output (console)
223
+
224
+ ```text
225
+ ==========================
226
+ funcC (6000.7ms)
227
+ └── funcB (3000.44ms)
228
+ └── funcA (1000.19ms)
229
+ ```
230
+
231
+ - Output (` ros2 topic echo /processing_time ` )
232
+
233
+ ``` text
234
+ nodes:
235
+ - id: 1
236
+ name: funcC
237
+ processing_time: 6000.659
238
+ parent_id: 0
239
+ - id: 2
240
+ name: funcB
241
+ processing_time: 3000.415
242
+ parent_id: 1
243
+ - id: 3
244
+ name: funcA
245
+ processing_time: 1000.181
246
+ parent_id: 2
247
+ ---
248
+ ```
249
+
250
+ - Output (` ros2 topic echo /processing_time_str --field data ` )
251
+
252
+ ``` text
253
+ funcC (6000.67ms)
254
+ └── funcB (3000.42ms)
255
+ └── funcA (1000.19ms)
256
+
257
+ ---
258
+ ```
0 commit comments