Skip to content

Commit 5ab1804

Browse files
authored
feat(mpc): calculate mpc predicted trajectory in the world coordinate to improve accuracy (#5576)
* remake Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * remove maybe_unused in decleration Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * support two predicted trajectories in world and Frenet coordinate Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * fix test Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> --------- Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
1 parent a4c9207 commit 5ab1804

19 files changed

+560
-185
lines changed

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp

+17-13
Original file line numberDiff line numberDiff line change
@@ -221,6 +221,7 @@ class MPC
221221

222222
double m_min_prediction_length = 5.0; // Minimum prediction distance.
223223

224+
rclcpp::Publisher<Trajectory>::SharedPtr m_debug_frenet_predicted_trajectory_pub;
224225
/**
225226
* @brief Get variables for MPC calculation.
226227
* @param trajectory The reference trajectory.
@@ -333,6 +334,19 @@ class MPC
333334
const MPCMatrix & m, const MatrixXd & x0, const MatrixXd & Uex, const double u_filtered,
334335
const float current_steer, const double predict_dt) const;
335336

337+
/**
338+
* @brief calculate predicted trajectory
339+
* @param mpc_matrix The MPC matrix used in the mpc problem.
340+
* @param x0 initial state used in the mpc problem.
341+
* @param Uex optimized input.
342+
* @param mpc_resampled_ref_traj reference trajectory resampled in the mpc time-step
343+
* @param dt delta time used in the mpc problem.
344+
* @return predicted path
345+
*/
346+
Trajectory calculatePredictedTrajectory(
347+
const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
348+
const MPCTrajectory & mpc_resampled_ref_traj, const double dt) const;
349+
336350
/**
337351
* @brief Check if the MPC matrix has any invalid values.
338352
* @param m The MPC matrix to check.
@@ -352,18 +366,6 @@ class MPC
352366
: m_param.nominal_weight;
353367
}
354368

355-
/**
356-
* @brief Calculate the predicted trajectory for the ego vehicle based on the MPC result.
357-
* @param mpc_resampled_reference_trajectory The resampled reference trajectory.
358-
* @param mpc_matrix The MPC matrix used for optimization.
359-
* @param x0_delayed The delayed initial state vector.
360-
* @param Uex The optimized input vector.
361-
* @return The predicted trajectory.
362-
*/
363-
Trajectory calcPredictedTrajectory(
364-
const MPCTrajectory & mpc_resampled_reference_trajectory, const MPCMatrix & mpc_matrix,
365-
const VectorXd & x0_delayed, const VectorXd & Uex) const;
366-
367369
/**
368370
* @brief Generate diagnostic data for debugging purposes.
369371
* @param reference_trajectory The reference trajectory.
@@ -424,8 +426,10 @@ class MPC
424426
double ego_nearest_dist_threshold = 3.0; // Threshold for nearest index search based on distance.
425427
double ego_nearest_yaw_threshold = M_PI_2; // Threshold for nearest index search based on yaw.
426428

429+
bool m_debug_publish_predicted_trajectory = false; // Flag to publish debug predicted trajectory
430+
427431
//!< Constructor.
428-
MPC() = default;
432+
explicit MPC(rclcpp::Node & node);
429433

430434
/**
431435
* @brief Calculate control command using the MPC algorithm.

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase
9191
// trajectory buffer for detecting new trajectory
9292
std::deque<Trajectory> m_trajectory_buffer;
9393

94-
MPC m_mpc; // MPC object for trajectory following.
94+
std::unique_ptr<MPC> m_mpc; // MPC object for trajectory following.
9595

9696
// Check is mpc output converged
9797
bool m_is_mpc_history_filled{false};

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,12 @@ class MPCTrajectory
8585
*/
8686
size_t size() const;
8787

88+
/**
89+
* @brief get trajectory point at index i
90+
* @return trajectory point at index i
91+
*/
92+
MPCTrajectoryPoint at(const size_t i) const;
93+
8894
/**
8995
* @return true if the components sizes are all 0 or are inconsistent
9096
*/

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp

+15
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,13 @@ Trajectory convertToAutowareTrajectory(const MPCTrajectory & input);
9292
*/
9393
void calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory, std::vector<double> & arc_length);
9494

95+
/**
96+
* @brief calculate the arc length of the given trajectory
97+
* @param [in] trajectory trajectory for which to calculate the arc length
98+
* @return total arc length
99+
*/
100+
double calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory);
101+
95102
/**
96103
* @brief resample the given trajectory with the given fixed interval
97104
* @param [in] input trajectory to resample
@@ -194,6 +201,14 @@ double calcStopDistance(const Trajectory & current_trajectory, const int origin)
194201
void extendTrajectoryInYawDirection(
195202
const double yaw, const double interval, const bool is_forward_shift, MPCTrajectory & traj);
196203

204+
/**
205+
* @brief clip trajectory size by length
206+
* @param [in] trajectory original trajectory
207+
* @param [in] length clip length
208+
* @return clipped trajectory
209+
*/
210+
MPCTrajectory clipTrajectoryByLength(const MPCTrajectory & trajectory, const double length);
211+
197212
/**
198213
* @brief Updates the value of a parameter with the given name.
199214
* @tparam T The type of the parameter value.

control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,16 @@ class DynamicsBicycleModel : public VehicleModelInterface
103103

104104
std::string modelName() override { return "dynamics"; };
105105

106+
MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate(
107+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
108+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
109+
const MPCTrajectory & reference_trajectory, const double dt) const override;
110+
111+
MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate(
112+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
113+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
114+
const MPCTrajectory & reference_trajectory, const double dt) const override;
115+
106116
private:
107117
double m_lf; //!< @brief length from center of mass to front wheel [m]
108118
double m_lr; //!< @brief length from center of mass to rear wheel [m]

control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,16 @@ class KinematicsBicycleModel : public VehicleModelInterface
9191

9292
std::string modelName() override { return "kinematics"; };
9393

94+
MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate(
95+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
96+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
97+
const MPCTrajectory & reference_trajectory, const double dt) const override;
98+
99+
MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate(
100+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
101+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
102+
const MPCTrajectory & reference_trajectory, const double dt) const override;
103+
94104
private:
95105
double m_steer_lim; //!< @brief steering angle limit [rad]
96106
double m_steer_tau; //!< @brief steering time constant for 1d-model [s]

control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,16 @@ class KinematicsBicycleModelNoDelay : public VehicleModelInterface
8787

8888
std::string modelName() override { return "kinematics_no_delay"; };
8989

90+
MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate(
91+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
92+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
93+
const MPCTrajectory & reference_trajectory, const double dt) const override;
94+
95+
MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate(
96+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
97+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
98+
const MPCTrajectory & reference_trajectory, const double dt) const override;
99+
90100
private:
91101
double m_steer_lim; //!< @brief steering angle limit [rad]
92102
};

control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp

+42-4
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
1616
#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_
1717

18+
#include "mpc_lateral_controller/mpc_trajectory.hpp"
19+
1820
#include <Eigen/Core>
1921

2022
#include <string>
@@ -55,25 +57,25 @@ class VehicleModelInterface
5557
* @brief get state x dimension
5658
* @return state dimension
5759
*/
58-
int getDimX();
60+
int getDimX() const;
5961

6062
/**
6163
* @brief get input u dimension
6264
* @return input dimension
6365
*/
64-
int getDimU();
66+
int getDimU() const;
6567

6668
/**
6769
* @brief get output y dimension
6870
* @return output dimension
6971
*/
70-
int getDimY();
72+
int getDimY() const;
7173

7274
/**
7375
* @brief get wheelbase of the vehicle
7476
* @return wheelbase value [m]
7577
*/
76-
double getWheelbase();
78+
double getWheelbase() const;
7779

7880
/**
7981
* @brief set velocity
@@ -109,6 +111,42 @@ class VehicleModelInterface
109111
* @brief returns model name e.g. kinematics, dynamics
110112
*/
111113
virtual std::string modelName() = 0;
114+
115+
/**
116+
* @brief Calculate the predicted trajectory for the ego vehicle based on the MPC result in world
117+
* coordinate
118+
* @param a_d The MPC A matrix used for optimization.
119+
* @param b_d The MPC B matrix used for optimization.
120+
* @param c_d The MPC C matrix used for optimization.
121+
* @param w_d The MPC W matrix used for optimization.
122+
* @param x0 initial state vector.
123+
* @param Uex The optimized input vector.
124+
* @param reference_trajectory The resampled reference trajectory.
125+
* @param dt delta time used in the optimization
126+
* @return The predicted trajectory.
127+
*/
128+
virtual MPCTrajectory calculatePredictedTrajectoryInWorldCoordinate(
129+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
130+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
131+
const MPCTrajectory & reference_trajectory, const double dt) const = 0;
132+
133+
/**
134+
* @brief Calculate the predicted trajectory for the ego vehicle based on the MPC result in Frenet
135+
* Coordinate
136+
* @param a_d The MPC A matrix used for optimization.
137+
* @param b_d The MPC B matrix used for optimization.
138+
* @param c_d The MPC C matrix used for optimization.
139+
* @param w_d The MPC W matrix used for optimization.
140+
* @param x0 initial state vector.
141+
* @param Uex The optimized input vector.
142+
* @param reference_trajectory The resampled reference trajectory.
143+
* @param dt delta time used in the optimization
144+
* @return The predicted trajectory.
145+
*/
146+
virtual MPCTrajectory calculatePredictedTrajectoryInFrenetCoordinate(
147+
const Eigen::MatrixXd & a_d, const Eigen::MatrixXd & b_d, const Eigen::MatrixXd & c_d,
148+
const Eigen::MatrixXd & w_d, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
149+
const MPCTrajectory & reference_trajectory, const double dt) const = 0;
112150
};
113151
} // namespace autoware::motion::control::mpc_lateral_controller
114152
#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_

control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -83,3 +83,5 @@
8383
mass_rr: 600.0
8484
cf: 155494.663
8585
cr: 155494.663
86+
87+
debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate

control/mpc_lateral_controller/src/mpc.cpp

+38-26
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "interpolation/linear_interpolation.hpp"
1818
#include "motion_utils/trajectory/trajectory.hpp"
1919
#include "mpc_lateral_controller/mpc_utils.hpp"
20+
#include "rclcpp/rclcpp.hpp"
2021
#include "tier4_autoware_utils/math/unit_conversion.hpp"
2122

2223
#include <algorithm>
@@ -28,6 +29,12 @@ using tier4_autoware_utils::calcDistance2d;
2829
using tier4_autoware_utils::normalizeRadian;
2930
using tier4_autoware_utils::rad2deg;
3031

32+
MPC::MPC(rclcpp::Node & node)
33+
{
34+
m_debug_frenet_predicted_trajectory_pub = node.create_publisher<Trajectory>(
35+
"~/debug/predicted_trajectory_in_frenet_coordinate", rclcpp::QoS(1));
36+
}
37+
3138
bool MPC::calculateMPC(
3239
const SteeringReport & current_steer, const Odometry & current_kinematics,
3340
AckermannLateralCommand & ctrl_cmd, Trajectory & predicted_trajectory,
@@ -97,9 +104,9 @@ bool MPC::calculateMPC(
97104
m_raw_steer_cmd_pprev = m_raw_steer_cmd_prev;
98105
m_raw_steer_cmd_prev = Uex(0);
99106

100-
// calculate predicted trajectory
107+
/* calculate predicted trajectory */
101108
predicted_trajectory =
102-
calcPredictedTrajectory(mpc_resampled_ref_trajectory, mpc_matrix, x0_delayed, Uex);
109+
calculatePredictedTrajectory(mpc_matrix, x0, Uex, mpc_resampled_ref_trajectory, prediction_dt);
103110

104111
// prepare diagnostic message
105112
diagnostic =
@@ -108,30 +115,6 @@ bool MPC::calculateMPC(
108115
return true;
109116
}
110117

111-
Trajectory MPC::calcPredictedTrajectory(
112-
const MPCTrajectory & mpc_resampled_ref_trajectory, const MPCMatrix & mpc_matrix,
113-
const VectorXd & x0_delayed, const VectorXd & Uex) const
114-
{
115-
const VectorXd Xex = mpc_matrix.Aex * x0_delayed + mpc_matrix.Bex * Uex + mpc_matrix.Wex;
116-
MPCTrajectory mpc_predicted_traj;
117-
const auto & traj = mpc_resampled_ref_trajectory;
118-
for (int i = 0; i < m_param.prediction_horizon; ++i) {
119-
const int DIM_X = m_vehicle_model_ptr->getDimX();
120-
const double lat_error = Xex(i * DIM_X);
121-
const double yaw_error = Xex(i * DIM_X + 1);
122-
const double x = traj.x.at(i) - std::sin(traj.yaw.at(i)) * lat_error;
123-
const double y = traj.y.at(i) + std::cos(traj.yaw.at(i)) * lat_error;
124-
const double z = traj.z.at(i);
125-
const double yaw = traj.yaw.at(i) + yaw_error;
126-
const double vx = traj.vx.at(i);
127-
const double k = traj.k.at(i);
128-
const double smooth_k = traj.smooth_k.at(i);
129-
const double relative_time = traj.relative_time.at(i);
130-
mpc_predicted_traj.push_back(x, y, z, yaw, vx, k, smooth_k, relative_time);
131-
}
132-
return MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj);
133-
}
134-
135118
Float32MultiArrayStamped MPC::generateDiagData(
136119
const MPCTrajectory & reference_trajectory, const MPCData & mpc_data,
137120
const MPCMatrix & mpc_matrix, const AckermannLateralCommand & ctrl_cmd, const VectorXd & Uex,
@@ -794,6 +777,35 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
794777
return steer_rate_limits;
795778
}
796779

780+
Trajectory MPC::calculatePredictedTrajectory(
781+
const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
782+
const MPCTrajectory & reference_trajectory, const double dt) const
783+
{
784+
const auto predicted_mpc_trajectory =
785+
m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate(
786+
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
787+
dt);
788+
789+
// do not over the reference trajectory
790+
const auto predicted_length = MPCUtils::calcMPCTrajectoryArcLength(reference_trajectory);
791+
const auto clipped_trajectory =
792+
MPCUtils::clipTrajectoryByLength(predicted_mpc_trajectory, predicted_length);
793+
794+
const auto predicted_trajectory = MPCUtils::convertToAutowareTrajectory(clipped_trajectory);
795+
796+
// Publish trajectory in relative coordinate for debug purpose.
797+
if (m_debug_publish_predicted_trajectory) {
798+
const auto frenet = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate(
799+
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
800+
dt);
801+
const auto frenet_clipped = MPCUtils::convertToAutowareTrajectory(
802+
MPCUtils::clipTrajectoryByLength(frenet, predicted_length));
803+
m_debug_frenet_predicted_trajectory_pub->publish(frenet_clipped);
804+
}
805+
806+
return predicted_trajectory;
807+
}
808+
797809
bool MPC::isValid(const MPCMatrix & m) const
798810
{
799811
if (

0 commit comments

Comments
 (0)