@@ -49,56 +49,80 @@ explicit TimeKeeper(Reporters... reporters);
49
49
- Ends tracking the processing time of a function.
50
50
- `func_name`: Name of the function to end tracking.
51
51
52
+ ##### Note
53
+
54
+ - It's possible to start and end time measurements using `start_track` and `end_track` as shown below:
55
+
56
+ ```cpp
57
+ time_keeper.start_track("example_function");
58
+ // Your function code here
59
+ time_keeper.end_track("example_function");
60
+ ```
61
+
62
+ - For safety and to ensure proper tracking, it is recommended to use ` ScopedTimeTrack ` .
63
+
52
64
##### Example
53
65
54
66
``` cpp
55
- #include "autoware/universe_utils/system/time_keeper.hpp"
56
-
57
67
#include < rclcpp/rclcpp.hpp>
58
68
69
+ #include < std_msgs/msg/string.hpp>
70
+
71
+ #include < chrono>
59
72
#include < iostream>
60
73
#include < memory>
74
+ #include < thread>
75
+
76
+ class ExampleNode : public rclcpp :: Node
77
+ {
78
+ public:
79
+ ExampleNode () : Node("time_keeper_example")
80
+ {
81
+ publisher_ =
82
+ create_publisher< autoware::universe_utils::ProcessingTimeDetail > ("processing_time", 1);
83
+
84
+ time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(publisher_, &std::cerr);
85
+ // You can also add a reporter later by add_reporter.
86
+ // time_keeper_->add_reporter(publisher_);
87
+ // time_keeper_->add_reporter(&std::cerr);
88
+
89
+ timer_ = create_wall_timer(std::chrono::seconds(1), std::bind(&ExampleNode::func_a, this));
90
+ }
91
+
92
+ private:
93
+ std::shared_ptr< autoware::universe_utils::TimeKeeper > time_keeper_ ;
94
+ rclcpp::Publisher< autoware::universe_utils::ProcessingTimeDetail > ::SharedPtr publisher_ ;
95
+ rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_str_ ;
96
+ rclcpp::TimerBase::SharedPtr timer_ ;
97
+
98
+ void func_a()
99
+ {
100
+ // Start constructing ProcessingTimeTree (because func_a is the root function)
101
+ autoware::universe_utils::ScopedTimeTrack st("func_a", * time_keeper_ );
102
+ std::this_thread::sleep_for(std::chrono::milliseconds(1));
103
+ func_b();
104
+ // End constructing ProcessingTimeTree. After this, the tree will be reported (publishing
105
+ // message and outputting to std::cerr)
106
+ }
107
+
108
+ void func_b()
109
+ {
110
+ autoware::universe_utils::ScopedTimeTrack st("func_b", * time_keeper_ );
111
+ std::this_thread::sleep_for(std::chrono::milliseconds(2));
112
+ func_c();
113
+ }
114
+
115
+ void func_c()
116
+ {
117
+ autoware::universe_utils::ScopedTimeTrack st("func_c", * time_keeper_ );
118
+ std::this_thread::sleep_for(std::chrono::milliseconds(3));
119
+ }
120
+ };
61
121
62
122
int main (int argc, char ** argv)
63
123
{
64
124
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
-
125
+ auto node = std::make_shared<ExampleNode >();
102
126
rclcpp::spin(node);
103
127
rclcpp::shutdown();
104
128
return 0;
@@ -109,38 +133,28 @@ int main(int argc, char ** argv)
109
133
110
134
```text
111
135
==========================
112
- funcC (6000.7ms )
113
- └── funcB (3000.44ms )
114
- └── funcA (1000.19ms )
136
+ func_a (6.382ms )
137
+ └── func_b (5.243ms )
138
+ └── func_c (3.146ms )
115
139
```
116
140
117
141
- Output (` ros2 topic echo /processing_time ` )
118
142
119
143
``` text
144
+ ---
120
145
nodes:
121
146
- id: 1
122
- name: funcC
123
- processing_time: 6000.659
147
+ name: func_a
148
+ processing_time: 6.397
124
149
parent_id: 0
125
150
- id: 2
126
- name: funcB
127
- processing_time: 3000.415
151
+ name: func_b
152
+ processing_time: 5.263
128
153
parent_id: 1
129
154
- id: 3
130
- name: funcA
131
- processing_time: 1000.181
155
+ name: func_c
156
+ processing_time: 3.129
132
157
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
158
```
145
159
146
160
#### ` autoware::universe_utils::ScopedTimeTrack `
@@ -165,94 +179,3 @@ ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper);
165
179
```
166
180
167
181
- 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