@@ -186,6 +186,53 @@ DiagnosticStatus ControlEvaluatorNode::generateYawDeviationDiagnosticStatus(
186
186
return status;
187
187
}
188
188
189
+ DiagnosticStatus ControlEvaluatorNode::generateGoalLongitudinalDeviationDiagnosticStatus (
190
+ const Pose & ego_pose)
191
+ {
192
+ DiagnosticStatus status;
193
+ const double longitudinal_deviation =
194
+ metrics::calcLongitudinalDeviation (route_handler_.getGoalPose (), ego_pose.position );
195
+
196
+ status.level = status.OK ;
197
+ status.name = " goal_longitudinal_deviation" ;
198
+ diagnostic_msgs::msg::KeyValue key_value;
199
+ key_value.key = " metrics_value" ;
200
+ key_value.value = std::to_string (longitudinal_deviation);
201
+ status.values .push_back (key_value);
202
+ return status;
203
+ }
204
+
205
+ DiagnosticStatus ControlEvaluatorNode::generateGoalLateralDeviationDiagnosticStatus (
206
+ const Pose & ego_pose)
207
+ {
208
+ DiagnosticStatus status;
209
+ const double lateral_deviation =
210
+ metrics::calcLateralDeviation (route_handler_.getGoalPose (), ego_pose.position );
211
+
212
+ status.level = status.OK ;
213
+ status.name = " goal_lateral_deviation" ;
214
+ diagnostic_msgs::msg::KeyValue key_value;
215
+ key_value.key = " metrics_value" ;
216
+ key_value.value = std::to_string (lateral_deviation);
217
+ status.values .push_back (key_value);
218
+ return status;
219
+ }
220
+
221
+ DiagnosticStatus ControlEvaluatorNode::generateGoalYawDeviationDiagnosticStatus (
222
+ const Pose & ego_pose)
223
+ {
224
+ DiagnosticStatus status;
225
+ const double yaw_deviation = metrics::calcYawDeviation (route_handler_.getGoalPose (), ego_pose);
226
+
227
+ status.level = status.OK ;
228
+ status.name = " goal_yaw_deviation" ;
229
+ diagnostic_msgs::msg::KeyValue key_value;
230
+ key_value.key = " metrics_value" ;
231
+ key_value.value = std::to_string (yaw_deviation);
232
+ status.values .push_back (key_value);
233
+ return status;
234
+ }
235
+
189
236
void ControlEvaluatorNode::onTimer ()
190
237
{
191
238
DiagnosticArray metrics_msg;
@@ -222,6 +269,10 @@ void ControlEvaluatorNode::onTimer()
222
269
if (odom && route_handler_.isHandlerReady ()) {
223
270
const Pose ego_pose = odom->pose .pose ;
224
271
metrics_msg.status .push_back (generateLaneletDiagnosticStatus (ego_pose));
272
+
273
+ metrics_msg.status .push_back (generateGoalLongitudinalDeviationDiagnosticStatus (ego_pose));
274
+ metrics_msg.status .push_back (generateGoalLateralDeviationDiagnosticStatus (ego_pose));
275
+ metrics_msg.status .push_back (generateGoalYawDeviationDiagnosticStatus (ego_pose));
225
276
}
226
277
227
278
if (odom && acc) {
0 commit comments