@@ -120,6 +120,86 @@ rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node)
120
120
return sub_opt;
121
121
}
122
122
123
+ visualization_msgs::msg::Marker create_polyhedron_marker (const EntityParams & params)
124
+ {
125
+ visualization_msgs::msg::Marker marker;
126
+ marker.header .frame_id = " map" ;
127
+ marker.header .stamp = rclcpp::Time (0 );
128
+ marker.ns = " entity" ;
129
+ marker.id = 0 ;
130
+ marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
131
+ marker.action = visualization_msgs::msg::Marker::ADD;
132
+
133
+ marker.pose .position .x = params.x ;
134
+ marker.pose .position .y = params.y ;
135
+ marker.pose .position .z = params.z ;
136
+
137
+ tf2::Quaternion quaternion;
138
+ quaternion.setRPY (
139
+ tier4_autoware_utils::deg2rad (params.roll ), tier4_autoware_utils::deg2rad (params.pitch ),
140
+ tier4_autoware_utils::deg2rad (params.yaw ));
141
+ marker.pose .orientation = tf2::toMsg (quaternion);
142
+
143
+ marker.scale .x = 0.1 ; // Line width
144
+
145
+ marker.color .a = 1.0 ; // Alpha
146
+ marker.color .r = 1.0 ;
147
+ marker.color .g = 0.0 ;
148
+ marker.color .b = 0.0 ;
149
+
150
+ // Define the 8 corners of the polyhedron
151
+ geometry_msgs::msg::Point p1, p2, p3, p4, p5, p6, p7, p8;
152
+
153
+ p1.x = params.x_l / 2.0 ;
154
+ p1.y = params.y_l / 2.0 ;
155
+ p1.z = params.z_l / 2.0 ;
156
+ p2.x = -params.x_l / 2.0 ;
157
+ p2.y = params.y_l / 2.0 ;
158
+ p2.z = params.z_l / 2.0 ;
159
+ p3.x = -params.x_l / 2.0 ;
160
+ p3.y = -params.y_l / 2.0 ;
161
+ p3.z = params.z_l / 2.0 ;
162
+ p4.x = params.x_l / 2.0 ;
163
+ p4.y = -params.y_l / 2.0 ;
164
+ p4.z = params.z_l / 2.0 ;
165
+ p5.x = params.x_l / 2.0 ;
166
+ p5.y = params.y_l / 2.0 ;
167
+ p5.z = -params.z_l / 2.0 ;
168
+ p6.x = -params.x_l / 2.0 ;
169
+ p6.y = params.y_l / 2.0 ;
170
+ p6.z = -params.z_l / 2.0 ;
171
+ p7.x = -params.x_l / 2.0 ;
172
+ p7.y = -params.y_l / 2.0 ;
173
+ p7.z = -params.z_l / 2.0 ;
174
+ p8.x = params.x_l / 2.0 ;
175
+ p8.y = -params.y_l / 2.0 ;
176
+ p8.z = -params.z_l / 2.0 ;
177
+
178
+ // Add points to the marker
179
+ marker.points .push_back (p1);
180
+ marker.points .push_back (p2);
181
+ marker.points .push_back (p3);
182
+ marker.points .push_back (p4);
183
+ marker.points .push_back (p1);
184
+
185
+ marker.points .push_back (p5);
186
+ marker.points .push_back (p6);
187
+ marker.points .push_back (p7);
188
+ marker.points .push_back (p8);
189
+ marker.points .push_back (p5);
190
+
191
+ marker.points .push_back (p1);
192
+ marker.points .push_back (p5);
193
+ marker.points .push_back (p6);
194
+ marker.points .push_back (p2);
195
+ marker.points .push_back (p3);
196
+ marker.points .push_back (p7);
197
+ marker.points .push_back (p4);
198
+ marker.points .push_back (p8);
199
+
200
+ return marker;
201
+ }
202
+
123
203
std::vector<std::string> split (const std::string & str, char delimiter)
124
204
{
125
205
std::vector<std::string> elements;
@@ -131,6 +211,11 @@ std::vector<std::string> split(const std::string & str, char delimiter)
131
211
return elements;
132
212
}
133
213
214
+ bool does_folder_exist (const std::string & path)
215
+ {
216
+ return std::filesystem::exists (path) && std::filesystem::is_directory (path);
217
+ }
218
+
134
219
size_t get_index_after_distance (
135
220
const Trajectory & traj, const size_t curr_id, const double distance)
136
221
{
@@ -410,7 +495,7 @@ void write_results(
410
495
}
411
496
412
497
// tmp map to store latency results for statistics
413
- std::map<std::string, std::vector<std::pair< double , double >>> tmp_latency_map;
498
+ std::map<std::string, std::vector<std::tuple< double , double , double >>> tmp_latency_map;
414
499
415
500
size_t test_count = 0 ;
416
501
for (const auto & pipeline_map : pipeline_map_vector) {
@@ -444,7 +529,8 @@ void write_results(
444
529
const auto total_latency =
445
530
calculate_time_diff_ms (spawn_cmd_time, reaction.published_stamp );
446
531
file << node_latency << " - " << pipeline_latency << " - " << total_latency << " ," ;
447
- tmp_latency_map[node_name].emplace_back (node_latency, total_latency);
532
+ tmp_latency_map[node_name].emplace_back (
533
+ std::make_tuple (node_latency, pipeline_latency, total_latency));
448
534
} else {
449
535
const auto & prev_reaction = pipeline_reactions[j - 1 ].second ;
450
536
const auto node_latency =
@@ -454,7 +540,8 @@ void write_results(
454
540
const auto total_latency =
455
541
calculate_time_diff_ms (spawn_cmd_time, reaction.published_stamp );
456
542
file << node_latency << " - " << pipeline_latency << " - " << total_latency << " ," ;
457
- tmp_latency_map[node_name].emplace_back (node_latency, total_latency);
543
+ tmp_latency_map[node_name].emplace_back (
544
+ std::make_tuple (node_latency, pipeline_latency, total_latency));
458
545
}
459
546
}
460
547
file << " \n " ;
@@ -465,27 +552,36 @@ void write_results(
465
552
466
553
file << " \n Statistics\n " ;
467
554
file << " Node "
468
- " Name,Min-NL,Max-NL,Mean-NL,Median-NL,Std-Dev-NL,Min-TL ,Max-TL ,Mean-TL ,Median-TL ,Std-Dev-"
469
- " TL\n " ;
555
+ " Name,Min-NL,Max-NL,Mean-NL,Median-NL,Std-Dev-NL,Min-PL ,Max-PL ,Mean-PL ,Median-PL ,Std-Dev-"
556
+ " PL,Min-TL,Max-TL,Mean-TL,Median-TL,Std-Dev- TL\n " ;
470
557
for (const auto & [node_name, latency_vec] : tmp_latency_map) {
471
558
file << node_name << " ," ;
559
+
472
560
std::vector<double > node_latencies;
561
+ std::vector<double > pipeline_latencies;
473
562
std::vector<double > total_latencies;
474
563
475
564
// Extract latencies
476
565
for (const auto & latencies : latency_vec) {
477
- node_latencies.push_back (latencies.first );
478
- total_latencies.push_back (latencies.second );
566
+ double node_latency, pipeline_latency, total_latency;
567
+ std::tie (node_latency, pipeline_latency, total_latency) = latencies;
568
+ node_latencies.push_back (node_latency);
569
+ pipeline_latencies.push_back (pipeline_latency);
570
+ total_latencies.push_back (total_latency);
479
571
}
480
572
481
573
const auto stats_node_latency = calculate_statistics (node_latencies);
574
+ const auto stats_pipeline_latency = calculate_statistics (pipeline_latencies);
482
575
const auto stats_total_latency = calculate_statistics (total_latencies);
483
576
484
577
file << stats_node_latency.min << " ," << stats_node_latency.max << " ,"
485
578
<< stats_node_latency.mean << " ," << stats_node_latency.median << " ,"
486
- << stats_node_latency.std_dev << " ," << stats_total_latency.min << " ,"
487
- << stats_total_latency.max << " ," << stats_total_latency.mean << " ,"
488
- << stats_total_latency.median << " ," << stats_total_latency.std_dev << " \n " ;
579
+ << stats_node_latency.std_dev << " ," << stats_pipeline_latency.min << " ,"
580
+ << stats_pipeline_latency.max << " ," << stats_pipeline_latency.mean << " ,"
581
+ << stats_pipeline_latency.median << " ," << stats_pipeline_latency.std_dev << " ,"
582
+ << stats_total_latency.min << " ," << stats_total_latency.max << " ,"
583
+ << stats_total_latency.mean << " ," << stats_total_latency.median << " ,"
584
+ << stats_total_latency.std_dev << " \n " ;
489
585
}
490
586
file.close ();
491
587
RCLCPP_INFO (node->get_logger (), " Results written to: %s" , ss.str ().c_str ());
0 commit comments