Skip to content

Commit b69fa76

Browse files
kyoichi-sugaharasaka1-s
authored andcommitted
feat(mpc_lateral_controller): add delayed initial state and debug trajectory publishing flags (#1721)
feat(mpc_lateral_controller): add flags for delayed initial state and debug trajectory publishing Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
1 parent 70a07eb commit b69fa76

File tree

6 files changed

+58
-22
lines changed

6 files changed

+58
-22
lines changed

control/autoware_mpc_lateral_controller/README.md

+7
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving.
9595
| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false |
9696
| admissible_position_error | double | stop vehicle when following position error is larger than this value [m] | 5.0 |
9797
| admissible_yaw_error_rad | double | stop vehicle when following yaw angle error is larger than this value [rad] | 1.57 |
98+
| use_delayed_initial_state | boolean | flag to use x0_delayed as initial state for predicted trajectory | true |
9899

99100
#### Path Smoothing
100101

@@ -202,6 +203,12 @@ Defined in the `steering_offset` namespace. This logic is designed as simple as
202203
| cf | double | front cornering power [N/rad] | 155494.663 |
203204
| cr | double | rear cornering power [N/rad] | 155494.663 |
204205

206+
#### Debug
207+
208+
| Name | Type | Description | Default value |
209+
| :------------------------- | :------ | :-------------------------------------------------------------------------------- | :------------ |
210+
| publish_debug_trajectories | boolean | publish predicted trajectory and resampled reference trajectory for debug purpose | true |
211+
205212
### How to tune MPC parameters
206213

207214
#### Set kinematics information

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp

+10-2
Original file line numberDiff line numberDiff line change
@@ -222,6 +222,7 @@ class MPC
222222
double m_min_prediction_length = 5.0; // Minimum prediction distance.
223223

224224
rclcpp::Publisher<Trajectory>::SharedPtr m_debug_frenet_predicted_trajectory_pub;
225+
rclcpp::Publisher<Trajectory>::SharedPtr m_debug_resampled_reference_trajectory_pub;
225226
/**
226227
* @brief Get variables for MPC calculation.
227228
* @param trajectory The reference trajectory.
@@ -341,11 +342,14 @@ class MPC
341342
* @param Uex optimized input.
342343
* @param mpc_resampled_ref_traj reference trajectory resampled in the mpc time-step
343344
* @param dt delta time used in the mpc problem.
345+
* @param coordinate String specifying the coordinate system ("world" or "frenet", default is
346+
* "world")
344347
* @return predicted path
345348
*/
346349
Trajectory calculatePredictedTrajectory(
347350
const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
348-
const MPCTrajectory & mpc_resampled_ref_traj, const double dt) const;
351+
const MPCTrajectory & reference_trajectory, const double dt,
352+
const std::string & coordinate = "world") const;
349353

350354
/**
351355
* @brief Check if the MPC matrix has any invalid values.
@@ -426,7 +430,11 @@ class MPC
426430
double ego_nearest_dist_threshold = 3.0; // Threshold for nearest index search based on distance.
427431
double ego_nearest_yaw_threshold = M_PI_2; // Threshold for nearest index search based on yaw.
428432

429-
bool m_debug_publish_predicted_trajectory = false; // Flag to publish debug predicted trajectory
433+
bool m_use_delayed_initial_state =
434+
true; // Flag to use x0_delayed as initial state for predicted trajectory
435+
436+
bool m_publish_debug_trajectories = false; // Flag to publish predicted trajectory and
437+
// resampled reference trajectory for debug purpose
430438

431439
//!< Constructor.
432440
explicit MPC(rclcpp::Node & node);

control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
66
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
77
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory
89

910
# -- path smoothing --
1011
enable_path_smoothing: false # flag for path smoothing
@@ -84,4 +85,4 @@
8485
cf: 155494.663
8586
cr: 155494.663
8687

87-
debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate
88+
publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose

control/autoware_mpc_lateral_controller/src/mpc.cpp

+34-17
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@ MPC::MPC(rclcpp::Node & node)
3333
{
3434
m_debug_frenet_predicted_trajectory_pub = node.create_publisher<Trajectory>(
3535
"~/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));
3638
}
3739

3840
bool MPC::calculateMPC(
@@ -104,8 +106,19 @@ bool MPC::calculateMPC(
104106
m_raw_steer_cmd_prev = Uex(0);
105107

106108
/* 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+
}
109122

110123
// prepare diagnostic message
111124
diagnostic =
@@ -310,6 +323,13 @@ std::pair<bool, MPCTrajectory> MPC::resampleMPCTrajectoryByTime(
310323
warn_throttle("calculateMPC: mpc resample error. stop mpc calculation. check code!");
311324
return {false, {}};
312325
}
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+
}
313333
return {true, output};
314334
}
315335

@@ -785,12 +805,21 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
785805

786806
Trajectory MPC::calculatePredictedTrajectory(
787807
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
789809
{
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(
792818
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
793819
dt);
820+
} else {
821+
throw std::invalid_argument("Invalid coordinate system specified. Use 'world' or 'frenet'.");
822+
}
794823

795824
// do not over the reference trajectory
796825
const auto predicted_length = MPCUtils::calcMPCTrajectoryArcLength(reference_trajectory);
@@ -799,18 +828,6 @@ Trajectory MPC::calculatePredictedTrajectory(
799828

800829
const auto predicted_trajectory = MPCUtils::convertToAutowareTrajectory(clipped_trajectory);
801830

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-
814831
return predicted_trajectory;
815832
}
816833

control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,9 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node)
134134
m_mpc->ego_nearest_dist_threshold = m_ego_nearest_dist_threshold;
135135
m_mpc->ego_nearest_yaw_threshold = m_ego_nearest_yaw_threshold;
136136

137-
m_mpc->m_debug_publish_predicted_trajectory = dp_bool("debug_publish_predicted_trajectory");
137+
m_mpc->m_use_delayed_initial_state = dp_bool("use_delayed_initial_state");
138+
139+
m_mpc->m_publish_debug_trajectories = dp_bool("publish_debug_trajectories");
138140

139141
m_pub_predicted_traj = node.create_publisher<Trajectory>("~/output/predicted_trajectory", 1);
140142
m_pub_debug_values =

control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
66
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
77
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory
89

910
# -- path smoothing --
1011
enable_path_smoothing: false # flag for path smoothing
@@ -75,4 +76,4 @@
7576
average_num: 1000
7677
steering_offset_limit: 0.02
7778

78-
debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate
79+
publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose

0 commit comments

Comments
 (0)