Skip to content

Commit

Permalink
publish metrics even if there is no metric in the MetricArray.
Browse files Browse the repository at this point in the history
Signed-off-by: xtk8532704 <1041084556@qq.com>
  • Loading branch information
xtk8532704 committed Nov 11, 2024
1 parent a6a0b16 commit 8852fa1
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 24 deletions.
18 changes: 10 additions & 8 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -401,6 +401,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
{
MarkerArray debug_markers;
MarkerArray virtual_wall_marker;
auto metrics = MetricArray();
checkCollision(debug_markers);

if (!collision_data_keeper_.checkCollisionExpired()) {
Expand All @@ -418,14 +419,12 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
}
addVirtualStopWallMarker(virtual_wall_marker);

// publish metrics
auto metric = Metric();
metric.name = "decision";
metric.value = "brake";
auto metrics = MetricArray();
metrics.stamp = get_clock()->now();
metrics.metric_array.push_back(metric);
metrics_pub_->publish(metrics);
{
auto metric = Metric();
metric.name = "decision";
metric.value = "brake";
metrics.metric_array.push_back(metric);
}

} else {
const std::string error_msg = "[AEB]: No Collision";
Expand All @@ -436,6 +435,9 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
// publish debug markers
debug_marker_publisher_->publish(debug_markers);
virtual_wall_publisher_->publish(virtual_wall_marker);
// publish metrics
metrics.stamp = get_clock()->now();
metrics_pub_->publish(metrics);
}

bool AEB::checkCollision(MarkerArray & debug_markers)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -221,11 +221,10 @@ void ControlEvaluatorNode::onTimer()
AddKinematicStateMetricMsg(*odom, *acc);
}

if (!metrics_msg_.metric_array.empty()) {
metrics_msg_.stamp = now();
metrics_pub_->publish(metrics_msg_);
metrics_msg_ = MetricArrayMsg{};
}
// Publish metrics
metrics_msg_.stamp = now();
metrics_pub_->publish(metrics_msg_);
metrics_msg_ = MetricArrayMsg{};
}
} // namespace control_diagnostics

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -243,11 +243,10 @@ void PlanningEvaluatorNode::onTimer()
onModifiedGoal(modified_goal_msg, ego_state_ptr);
}

if (!metrics_msg_.metric_array.empty()) {
metrics_msg_.stamp = now();
metrics_pub_->publish(metrics_msg_);
metrics_msg_ = MetricArrayMsg{};
}
// Publish metrics
metrics_msg_.stamp = now();
metrics_pub_->publish(metrics_msg_);
metrics_msg_ = MetricArrayMsg{};
}

void PlanningEvaluatorNode::onTrajectory(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -912,9 +912,7 @@ void PlannerInterface::publishMetrics(const rclcpp::Time & current_time)
addMetrics(debug_data_ptr_->stop_metrics);
addMetrics(debug_data_ptr_->slow_down_metrics);
addMetrics(debug_data_ptr_->cruise_metrics);
if (!metrics_msg.metric_array.empty()) {
metrics_pub_->publish(metrics_msg);
}
metrics_pub_->publish(metrics_msg);
clearMetrics();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -307,9 +307,7 @@ void MotionVelocityPlannerNode::on_trajectory(
processing_time_publisher_->publish(processing_time_msg);

std::shared_ptr<MetricArray> metrics = planner_manager_.get_metrics(get_clock()->now());
if (!metrics->metric_array.empty()) {
metrics_pub_->publish(*metrics);
}
metrics_pub_->publish(*metrics);
planner_manager_.clear_metrics();
}

Expand Down

0 comments on commit 8852fa1

Please sign in to comment.