@@ -33,6 +33,8 @@ MPC::MPC(rclcpp::Node & node)
33
33
{
34
34
m_debug_frenet_predicted_trajectory_pub = node.create_publisher <Trajectory>(
35
35
" ~/debug/predicted_trajectory_in_frenet_coordinate" , rclcpp::QoS (1 ));
36
+ m_debug_resampled_reference_trajectory_pub =
37
+ node.create_publisher <Trajectory>(" ~/debug/resampled_reference_trajectory" , rclcpp::QoS (1 ));
36
38
}
37
39
38
40
bool MPC::calculateMPC (
@@ -104,8 +106,19 @@ bool MPC::calculateMPC(
104
106
m_raw_steer_cmd_prev = Uex (0 );
105
107
106
108
/* calculate predicted trajectory */
107
- predicted_trajectory =
108
- calculatePredictedTrajectory (mpc_matrix, x0, Uex, mpc_resampled_ref_trajectory, prediction_dt);
109
+ Eigen::VectorXd initial_state = m_use_delayed_initial_state ? x0_delayed : x0;
110
+ predicted_trajectory = calculatePredictedTrajectory (
111
+ mpc_matrix, initial_state, Uex, mpc_resampled_ref_trajectory, prediction_dt, " world" );
112
+
113
+ // Publish predicted trajectories in different coordinates for debugging purposes
114
+ if (m_publish_debug_trajectories) {
115
+ // Calculate and publish predicted trajectory in Frenet coordinate
116
+ auto predicted_trajectory_frenet = calculatePredictedTrajectory (
117
+ mpc_matrix, initial_state, Uex, mpc_resampled_ref_trajectory, prediction_dt, " frenet" );
118
+ predicted_trajectory_frenet.header .stamp = m_clock->now ();
119
+ predicted_trajectory_frenet.header .frame_id = " map" ;
120
+ m_debug_frenet_predicted_trajectory_pub->publish (predicted_trajectory_frenet);
121
+ }
109
122
110
123
// prepare diagnostic message
111
124
diagnostic =
@@ -310,6 +323,13 @@ std::pair<bool, MPCTrajectory> MPC::resampleMPCTrajectoryByTime(
310
323
warn_throttle (" calculateMPC: mpc resample error. stop mpc calculation. check code!" );
311
324
return {false , {}};
312
325
}
326
+ // Publish resampled reference trajectory for debug purpose.
327
+ if (m_publish_debug_trajectories) {
328
+ auto converted_output = MPCUtils::convertToAutowareTrajectory (output);
329
+ converted_output.header .stamp = m_clock->now ();
330
+ converted_output.header .frame_id = " map" ;
331
+ m_debug_resampled_reference_trajectory_pub->publish (converted_output);
332
+ }
313
333
return {true , output};
314
334
}
315
335
@@ -785,12 +805,21 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
785
805
786
806
Trajectory MPC::calculatePredictedTrajectory (
787
807
const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
788
- const MPCTrajectory & reference_trajectory, const double dt) const
808
+ const MPCTrajectory & reference_trajectory, const double dt, const std::string & coordinate ) const
789
809
{
790
- const auto predicted_mpc_trajectory =
791
- m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate (
810
+ MPCTrajectory predicted_mpc_trajectory;
811
+
812
+ if (coordinate == " world" ) {
813
+ predicted_mpc_trajectory = m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate (
814
+ mpc_matrix.Aex , mpc_matrix.Bex , mpc_matrix.Cex , mpc_matrix.Wex , x0, Uex, reference_trajectory,
815
+ dt);
816
+ } else if (coordinate == " frenet" ) {
817
+ predicted_mpc_trajectory = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate (
792
818
mpc_matrix.Aex , mpc_matrix.Bex , mpc_matrix.Cex , mpc_matrix.Wex , x0, Uex, reference_trajectory,
793
819
dt);
820
+ } else {
821
+ throw std::invalid_argument (" Invalid coordinate system specified. Use 'world' or 'frenet'." );
822
+ }
794
823
795
824
// do not over the reference trajectory
796
825
const auto predicted_length = MPCUtils::calcMPCTrajectoryArcLength (reference_trajectory);
@@ -799,18 +828,6 @@ Trajectory MPC::calculatePredictedTrajectory(
799
828
800
829
const auto predicted_trajectory = MPCUtils::convertToAutowareTrajectory (clipped_trajectory);
801
830
802
- // Publish trajectory in relative coordinate for debug purpose.
803
- if (m_debug_publish_predicted_trajectory) {
804
- const auto frenet = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate (
805
- mpc_matrix.Aex , mpc_matrix.Bex , mpc_matrix.Cex , mpc_matrix.Wex , x0, Uex, reference_trajectory,
806
- dt);
807
- auto frenet_clipped = MPCUtils::convertToAutowareTrajectory (
808
- MPCUtils::clipTrajectoryByLength (frenet, predicted_length));
809
- frenet_clipped.header .stamp = m_clock->now ();
810
- frenet_clipped.header .frame_id = " map" ;
811
- m_debug_frenet_predicted_trajectory_pub->publish (frenet_clipped);
812
- }
813
-
814
831
return predicted_trajectory;
815
832
}
816
833
0 commit comments