Skip to content

Commit 3b6ef51

Browse files
author
Berkay Karaman
committed
feat: update stats, check path param, add marker, warn user for wrong reaction_chain
Signed-off-by: Berkay Karaman <berkay@leodrive.ai>
1 parent 08833c6 commit 3b6ef51

File tree

6 files changed

+147
-12
lines changed

6 files changed

+147
-12
lines changed

tools/reaction_analyzer/README.md

+5
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,11 @@ and `reaction_chain` list. `output_file_path` is the output file path is the pat
5454
will be stored. `test_iteration` defines how many tests will be performed. The `reaction_chain` list is the list of the
5555
pre-defined topics you want to measure their reaction times.
5656

57+
**IMPORTANT:** Ensure the `reaction_chain` list is correctly defined:
58+
59+
- For `perception_planning` mode, **do not** define `Control` nodes.
60+
- For `planning_control` mode, **do not** define `Perception` nodes.
61+
5762
### Prepared Test Environment
5863

5964
- Download the demonstration test map from the

tools/reaction_analyzer/include/reaction_analyzer_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,7 @@ class ReactionAnalyzerNode : public rclcpp::Node
9393
// Publishers
9494
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pub_initial_pose_;
9595
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_goal_pose_;
96+
rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr pub_marker_;
9697

9798
// Variables
9899
std::vector<PipelineMap> pipeline_map_vector_;
@@ -104,6 +105,7 @@ class ReactionAnalyzerNode : public rclcpp::Node
104105
bool is_initialization_requested{false};
105106
bool is_route_set_{false};
106107
size_t test_iteration_count_{0};
108+
visualization_msgs::msg::Marker entity_debug_marker_;
107109

108110
// Functions
109111
void init_analyzer_variables();

tools/reaction_analyzer/include/utils.hpp

+19
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
#include <autoware_internal_msgs/msg/published_time.hpp>
3131
#include <sensor_msgs/msg/point_cloud2.hpp>
3232
#include <unique_identifier_msgs/msg/uuid.hpp>
33+
#include <visualization_msgs/msg/marker.hpp>
3334

3435
#include <boost/uuid/string_generator.hpp>
3536
#include <boost/uuid/uuid.hpp>
@@ -40,6 +41,7 @@
4041
#include <pcl/point_types.h>
4142
#include <pcl_conversions/pcl_conversions.h>
4243

44+
#include <filesystem>
4345
#include <fstream>
4446
#include <map>
4547
#include <string>
@@ -253,6 +255,15 @@ PredictedObjects::SharedPtr create_entity_predicted_objects_ptr(const EntityPara
253255
*/
254256
rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node);
255257

258+
/**
259+
* @brief Creates a visualization marker for a polyhedron based on the provided entity parameters.
260+
*
261+
* @param params The parameters of the entity for which the marker is to be created. It includes the
262+
* position, orientation, and dimensions of the entity.
263+
* @return The created visualization marker for the polyhedron.
264+
*/
265+
visualization_msgs::msg::Marker create_polyhedron_marker(const EntityParams & params);
266+
256267
/**
257268
* @brief Splits a string by a given delimiter.
258269
*
@@ -263,6 +274,14 @@ rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node);
263274
*/
264275
std::vector<std::string> split(const std::string & str, char delimiter);
265276

277+
/**
278+
* @brief Checks if a folder exists.
279+
*
280+
* @param path The path to the folder.
281+
* @return True if the folder exists, false otherwise.
282+
*/
283+
bool does_folder_exist(const std::string & path);
284+
266285
/**
267286
* @brief Get the index of the trajectory point that is a certain distance away from the current
268287
* point.

tools/reaction_analyzer/src/reaction_analyzer_node.cpp

+11-2
Original file line numberDiff line numberDiff line change
@@ -68,9 +68,15 @@ ReactionAnalyzerNode::ReactionAnalyzerNode(rclcpp::NodeOptions node_options)
6868
return;
6969
}
7070

71+
node_params_.output_file_path = get_parameter("output_file_path").as_string();
72+
// Check if the output file path is valid
73+
if (!does_folder_exist(node_params_.output_file_path)) {
74+
RCLCPP_ERROR(get_logger(), "Output file path is not valid. Node couldn't be initialized.");
75+
return;
76+
}
77+
7178
node_params_.timer_period = get_parameter("timer_period").as_double();
7279
node_params_.test_iteration = get_parameter("test_iteration").as_int();
73-
node_params_.output_file_path = get_parameter("output_file_path").as_string();
7480
node_params_.spawn_time_after_init = get_parameter("spawn_time_after_init").as_double();
7581
node_params_.spawn_distance_threshold = get_parameter("spawn_distance_threshold").as_double();
7682

@@ -115,6 +121,7 @@ ReactionAnalyzerNode::ReactionAnalyzerNode(rclcpp::NodeOptions node_options)
115121
create_subscription_options(this));
116122

117123
pub_goal_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>("output/goal", rclcpp::QoS(1));
124+
pub_marker_ = create_publisher<visualization_msgs::msg::Marker>("~/debug", 10);
118125

119126
init_analyzer_variables();
120127

@@ -167,6 +174,8 @@ void ReactionAnalyzerNode::on_timer()
167174
return;
168175
}
169176

177+
pub_marker_->publish(entity_debug_marker_);
178+
170179
// Spawn the obstacle if the conditions are met
171180
spawn_obstacle(current_odometry_ptr->pose.pose.position);
172181

@@ -244,7 +253,7 @@ void ReactionAnalyzerNode::calculate_results(
244253
void ReactionAnalyzerNode::init_analyzer_variables()
245254
{
246255
entity_pose_ = create_entity_pose(node_params_.entity_params);
247-
256+
entity_debug_marker_ = create_polyhedron_marker(node_params_.entity_params);
248257
goal_pose_.pose = pose_params_to_pose(node_params_.goal_pose);
249258

250259
if (node_running_mode_ == RunningMode::PlanningControl) {

tools/reaction_analyzer/src/subscriber.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -162,10 +162,14 @@ std::optional<std::map<std::string, MessageBufferVariant>> SubscriberBase::get_m
162162
for (const auto & [key, variant] : message_buffers_) {
163163
if (auto * control_message = std::get_if<ControlCommandBuffer>(&variant)) {
164164
if (!control_message->second) {
165+
RCLCPP_WARN_THROTTLE(
166+
node_->get_logger(), *node_->get_clock(), 1000, "Waiting for %s to react", key.c_str());
165167
all_reacted = false;
166168
}
167169
} else if (auto * general_message = std::get_if<MessageBuffer>(&variant)) {
168170
if (!general_message->has_value()) {
171+
RCLCPP_WARN_THROTTLE(
172+
node_->get_logger(), *node_->get_clock(), 1000, "Waiting for %s to react", key.c_str());
169173
all_reacted = false;
170174
}
171175
}

tools/reaction_analyzer/src/utils.cpp

+106-10
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,86 @@ rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node)
120120
return sub_opt;
121121
}
122122

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+
123203
std::vector<std::string> split(const std::string & str, char delimiter)
124204
{
125205
std::vector<std::string> elements;
@@ -131,6 +211,11 @@ std::vector<std::string> split(const std::string & str, char delimiter)
131211
return elements;
132212
}
133213

214+
bool does_folder_exist(const std::string & path)
215+
{
216+
return std::filesystem::exists(path) && std::filesystem::is_directory(path);
217+
}
218+
134219
size_t get_index_after_distance(
135220
const Trajectory & traj, const size_t curr_id, const double distance)
136221
{
@@ -410,7 +495,7 @@ void write_results(
410495
}
411496

412497
// 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;
414499

415500
size_t test_count = 0;
416501
for (const auto & pipeline_map : pipeline_map_vector) {
@@ -444,7 +529,8 @@ void write_results(
444529
const auto total_latency =
445530
calculate_time_diff_ms(spawn_cmd_time, reaction.published_stamp);
446531
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));
448534
} else {
449535
const auto & prev_reaction = pipeline_reactions[j - 1].second;
450536
const auto node_latency =
@@ -454,7 +540,8 @@ void write_results(
454540
const auto total_latency =
455541
calculate_time_diff_ms(spawn_cmd_time, reaction.published_stamp);
456542
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));
458545
}
459546
}
460547
file << "\n";
@@ -465,27 +552,36 @@ void write_results(
465552

466553
file << "\nStatistics\n";
467554
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";
470557
for (const auto & [node_name, latency_vec] : tmp_latency_map) {
471558
file << node_name << ",";
559+
472560
std::vector<double> node_latencies;
561+
std::vector<double> pipeline_latencies;
473562
std::vector<double> total_latencies;
474563

475564
// Extract latencies
476565
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);
479571
}
480572

481573
const auto stats_node_latency = calculate_statistics(node_latencies);
574+
const auto stats_pipeline_latency = calculate_statistics(pipeline_latencies);
482575
const auto stats_total_latency = calculate_statistics(total_latencies);
483576

484577
file << stats_node_latency.min << "," << stats_node_latency.max << ","
485578
<< 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";
489585
}
490586
file.close();
491587
RCLCPP_INFO(node->get_logger(), "Results written to: %s", ss.str().c_str());

0 commit comments

Comments
 (0)