mpc.cpp 33 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809
  1. // Copyright 2018-2021 The Autoware Foundation
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #include "mpc_lateral_controller/mpc.hpp"
  15. #include "interpolation/linear_interpolation.hpp"
  16. #include "motion_utils/trajectory/trajectory.hpp"
  17. #include "mpc_lateral_controller/mpc_utils.hpp"
  18. #include "tier4_autoware_utils/math/unit_conversion.hpp"
  19. #include <algorithm>
  20. #include <limits>
  21. namespace autoware::motion::control::mpc_lateral_controller
  22. {
  23. using tier4_autoware_utils::calcDistance2d;
  24. using tier4_autoware_utils::normalizeRadian;
  25. using tier4_autoware_utils::rad2deg;
  26. bool MPC::calculateMPC(
  27. const SteeringReport & current_steer, const Odometry & current_kinematics,
  28. AckermannLateralCommand & ctrl_cmd, Trajectory & predicted_trajectory,
  29. Float32MultiArrayStamped & diagnostic)
  30. {
  31. // since the reference trajectory does not take into account the current velocity of the ego
  32. // vehicle, it needs to calculate the trajectory velocity considering the longitudinal dynamics.
  33. const auto reference_trajectory =
  34. applyVelocityDynamicsFilter(m_reference_trajectory, current_kinematics);
  35. // get the necessary data
  36. const auto [success_data, mpc_data] =
  37. getData(reference_trajectory, current_steer, current_kinematics);
  38. if (!success_data) {
  39. return fail_warn_throttle("fail to get MPC Data. Stop MPC.");
  40. }
  41. // calculate initial state of the error dynamics
  42. const auto x0 = getInitialState(mpc_data);
  43. // apply time delay compensation to the initial state
  44. const auto [success_delay, x0_delayed] =
  45. updateStateForDelayCompensation(reference_trajectory, mpc_data.nearest_time, x0);
  46. if (!success_delay) {
  47. return fail_warn_throttle("delay compensation failed. Stop MPC.");
  48. }
  49. // resample reference trajectory with mpc sampling time
  50. const double mpc_start_time = mpc_data.nearest_time + m_param.input_delay;
  51. const double prediction_dt =
  52. getPredictionDeltaTime(mpc_start_time, reference_trajectory, current_kinematics);
  53. const auto [success_resample, mpc_resampled_ref_trajectory] =
  54. resampleMPCTrajectoryByTime(mpc_start_time, prediction_dt, reference_trajectory);
  55. if (!success_resample) {
  56. return fail_warn_throttle("trajectory resampling failed. Stop MPC.");
  57. }
  58. // generate mpc matrix : predict equation Xec = Aex * x0 + Bex * Uex + Wex
  59. const auto mpc_matrix = generateMPCMatrix(mpc_resampled_ref_trajectory, prediction_dt);
  60. // solve Optimization problem
  61. const auto [success_opt, Uex] = executeOptimization(
  62. mpc_matrix, x0_delayed, prediction_dt, mpc_resampled_ref_trajectory,
  63. current_kinematics.twist.twist.linear.x);
  64. if (!success_opt) {
  65. return fail_warn_throttle("optimization failed. Stop MPC.");
  66. }
  67. // apply filters for the input limitation and low pass filter
  68. const double u_saturated = std::clamp(Uex(0), -m_steer_lim, m_steer_lim);
  69. const double u_filtered = m_lpf_steering_cmd.filter(u_saturated);
  70. // set control command
  71. ctrl_cmd.steering_tire_angle = static_cast<float>(u_filtered);
  72. ctrl_cmd.steering_tire_rotation_rate = static_cast<float>(calcDesiredSteeringRate(
  73. mpc_matrix, x0_delayed, Uex, u_filtered, current_steer.steering_tire_angle, prediction_dt));
  74. // save the control command for the steering prediction
  75. m_steering_predictor->storeSteerCmd(u_filtered);
  76. // save input to buffer for delay compensation
  77. m_input_buffer.push_back(ctrl_cmd.steering_tire_angle);
  78. m_input_buffer.pop_front();
  79. // save previous input for the mpc rate limit
  80. m_raw_steer_cmd_pprev = m_raw_steer_cmd_prev;
  81. m_raw_steer_cmd_prev = Uex(0);
  82. // calculate predicted trajectory
  83. predicted_trajectory =
  84. calcPredictedTrajectory(mpc_resampled_ref_trajectory, mpc_matrix, x0_delayed, Uex);
  85. // prepare diagnostic message
  86. diagnostic =
  87. generateDiagData(reference_trajectory, mpc_data, mpc_matrix, ctrl_cmd, Uex, current_kinematics);
  88. return true;
  89. }
  90. Trajectory MPC::calcPredictedTrajectory(
  91. const MPCTrajectory & mpc_resampled_ref_trajectory, const MPCMatrix & mpc_matrix,
  92. const VectorXd & x0_delayed, const VectorXd & Uex) const
  93. {
  94. const VectorXd Xex = mpc_matrix.Aex * x0_delayed + mpc_matrix.Bex * Uex + mpc_matrix.Wex;
  95. MPCTrajectory mpc_predicted_traj;
  96. const auto & traj = mpc_resampled_ref_trajectory;
  97. for (int i = 0; i < m_param.prediction_horizon; ++i) {
  98. const int DIM_X = m_vehicle_model_ptr->getDimX();
  99. const double lat_error = Xex(i * DIM_X);
  100. const double yaw_error = Xex(i * DIM_X + 1);
  101. const double x = traj.x.at(i) - std::sin(traj.yaw.at(i)) * lat_error;
  102. const double y = traj.y.at(i) + std::cos(traj.yaw.at(i)) * lat_error;
  103. const double z = traj.z.at(i);
  104. const double yaw = traj.yaw.at(i) + yaw_error;
  105. const double vx = traj.vx.at(i);
  106. const double k = traj.k.at(i);
  107. const double smooth_k = traj.smooth_k.at(i);
  108. const double relative_time = traj.relative_time.at(i);
  109. mpc_predicted_traj.push_back(x, y, z, yaw, vx, k, smooth_k, relative_time);
  110. }
  111. return MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj);
  112. }
  113. Float32MultiArrayStamped MPC::generateDiagData(
  114. const MPCTrajectory & reference_trajectory, const MPCData & mpc_data,
  115. const MPCMatrix & mpc_matrix, const AckermannLateralCommand & ctrl_cmd, const VectorXd & Uex,
  116. const Odometry & current_kinematics) const
  117. {
  118. Float32MultiArrayStamped diagnostic;
  119. // prepare diagnostic message
  120. const double nearest_k = reference_trajectory.k.at(mpc_data.nearest_idx);
  121. const double nearest_smooth_k = reference_trajectory.smooth_k.at(mpc_data.nearest_idx);
  122. const double wb = m_vehicle_model_ptr->getWheelbase();
  123. const double current_velocity = current_kinematics.twist.twist.linear.x;
  124. const double wz_predicted = current_velocity * std::tan(mpc_data.predicted_steer) / wb;
  125. const double wz_measured = current_velocity * std::tan(mpc_data.steer) / wb;
  126. const double wz_command = current_velocity * std::tan(ctrl_cmd.steering_tire_angle) / wb;
  127. typedef decltype(diagnostic.data)::value_type DiagnosticValueType;
  128. const auto append_diag = [&](const auto & val) -> void {
  129. diagnostic.data.push_back(static_cast<DiagnosticValueType>(val));
  130. };
  131. append_diag(ctrl_cmd.steering_tire_angle); // [0] final steering command (MPC + LPF)
  132. append_diag(Uex(0)); // [1] mpc calculation result
  133. append_diag(mpc_matrix.Uref_ex(0)); // [2] feed-forward steering value
  134. append_diag(std::atan(nearest_smooth_k * wb)); // [3] feed-forward steering value raw
  135. append_diag(mpc_data.steer); // [4] current steering angle
  136. append_diag(mpc_data.lateral_err); // [5] lateral error
  137. append_diag(tf2::getYaw(current_kinematics.pose.pose.orientation)); // [6] current_pose yaw
  138. append_diag(tf2::getYaw(mpc_data.nearest_pose.orientation)); // [7] nearest_pose yaw
  139. append_diag(mpc_data.yaw_err); // [8] yaw error
  140. append_diag(reference_trajectory.vx.at(mpc_data.nearest_idx)); // [9] reference velocity
  141. append_diag(current_velocity); // [10] measured velocity
  142. append_diag(wz_command); // [11] angular velocity from steer command
  143. append_diag(wz_measured); // [12] angular velocity from measured steer
  144. append_diag(current_velocity * nearest_smooth_k); // [13] angular velocity from path curvature
  145. append_diag(nearest_smooth_k); // [14] nearest path curvature (used for feed-forward)
  146. append_diag(nearest_k); // [15] nearest path curvature (not smoothed)
  147. append_diag(mpc_data.predicted_steer); // [16] predicted steer
  148. append_diag(wz_predicted); // [17] angular velocity from predicted steer
  149. return diagnostic;
  150. }
  151. void MPC::setReferenceTrajectory(
  152. const Trajectory & trajectory_msg, const TrajectoryFilteringParam & param,
  153. const Odometry & current_kinematics)
  154. {
  155. const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
  156. trajectory_msg.points, current_kinematics.pose.pose, ego_nearest_dist_threshold,
  157. ego_nearest_yaw_threshold);
  158. const double ego_offset_to_segment = motion_utils::calcLongitudinalOffsetToSegment(
  159. trajectory_msg.points, nearest_seg_idx, current_kinematics.pose.pose.position);
  160. const auto mpc_traj_raw = MPCUtils::convertToMPCTrajectory(trajectory_msg);
  161. // resampling
  162. const auto [success_resample, mpc_traj_resampled] = MPCUtils::resampleMPCTrajectoryByDistance(
  163. mpc_traj_raw, param.traj_resample_dist, nearest_seg_idx, ego_offset_to_segment);
  164. if (!success_resample) {
  165. warn_throttle("[setReferenceTrajectory] spline error when resampling by distance");
  166. return;
  167. }
  168. const auto is_forward_shift =
  169. motion_utils::isDrivingForward(mpc_traj_resampled.toTrajectoryPoints());
  170. // if driving direction is unknown, use previous value
  171. m_is_forward_shift = is_forward_shift ? is_forward_shift.get() : m_is_forward_shift;
  172. // path smoothing
  173. MPCTrajectory mpc_traj_smoothed = mpc_traj_resampled; // smooth filtered trajectory
  174. const int mpc_traj_resampled_size = static_cast<int>(mpc_traj_resampled.size());
  175. if (
  176. param.enable_path_smoothing && mpc_traj_resampled_size > 2 * param.path_filter_moving_ave_num) {
  177. using MoveAverageFilter::filt_vector;
  178. if (
  179. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.x) ||
  180. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.y) ||
  181. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.yaw) ||
  182. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.vx)) {
  183. RCLCPP_DEBUG(m_logger, "path callback: filtering error. stop filtering.");
  184. mpc_traj_smoothed = mpc_traj_resampled;
  185. }
  186. }
  187. /*
  188. * Extend terminal points
  189. * Note: The current MPC does not properly take into account the attitude angle at the end of the
  190. * path. By extending the end of the path in the attitude direction, the MPC can consider the
  191. * attitude angle well, resulting in improved control performance. If the trajectory is
  192. * well-defined considering the end point attitude angle, this feature is not necessary.
  193. */
  194. if (param.extend_trajectory_for_end_yaw_control) {
  195. MPCUtils::extendTrajectoryInYawDirection(
  196. mpc_traj_raw.yaw.back(), param.traj_resample_dist, m_is_forward_shift, mpc_traj_smoothed);
  197. }
  198. // calculate yaw angle
  199. MPCUtils::calcTrajectoryYawFromXY(mpc_traj_smoothed, m_is_forward_shift);
  200. MPCUtils::convertEulerAngleToMonotonic(mpc_traj_smoothed.yaw);
  201. // calculate curvature
  202. MPCUtils::calcTrajectoryCurvature(
  203. param.curvature_smoothing_num_traj, param.curvature_smoothing_num_ref_steer, mpc_traj_smoothed);
  204. // stop velocity at a terminal point
  205. mpc_traj_smoothed.vx.back() = 0.0;
  206. // add a extra point on back with extended time to make the mpc stable.
  207. auto last_point = mpc_traj_smoothed.back();
  208. last_point.relative_time += 100.0; // extra time to prevent mpc calc failure due to short time
  209. last_point.vx = 0.0; // stop velocity at a terminal point
  210. mpc_traj_smoothed.push_back(last_point);
  211. if (!mpc_traj_smoothed.size()) {
  212. RCLCPP_DEBUG(m_logger, "path callback: trajectory size is undesired.");
  213. return;
  214. }
  215. m_reference_trajectory = mpc_traj_smoothed;
  216. }
  217. void MPC::resetPrevResult(const SteeringReport & current_steer)
  218. {
  219. // Consider limit. The prev value larger than limitation brakes the optimization constraint and
  220. // results in optimization failure.
  221. const float steer_lim_f = static_cast<float>(m_steer_lim);
  222. m_raw_steer_cmd_prev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f);
  223. m_raw_steer_cmd_pprev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f);
  224. }
  225. std::pair<bool, MPCData> MPC::getData(
  226. const MPCTrajectory & traj, const SteeringReport & current_steer,
  227. const Odometry & current_kinematics)
  228. {
  229. const auto current_pose = current_kinematics.pose.pose;
  230. MPCData data;
  231. if (!MPCUtils::calcNearestPoseInterp(
  232. traj, current_pose, &(data.nearest_pose), &(data.nearest_idx), &(data.nearest_time),
  233. ego_nearest_dist_threshold, ego_nearest_yaw_threshold)) {
  234. warn_throttle("calculateMPC: error in calculating nearest pose. stop mpc.");
  235. return {false, MPCData{}};
  236. }
  237. // get data
  238. data.steer = static_cast<double>(current_steer.steering_tire_angle);
  239. data.lateral_err = MPCUtils::calcLateralError(current_pose, data.nearest_pose);
  240. data.yaw_err = normalizeRadian(
  241. tf2::getYaw(current_pose.orientation) - tf2::getYaw(data.nearest_pose.orientation));
  242. // get predicted steer
  243. data.predicted_steer = m_steering_predictor->calcSteerPrediction();
  244. // check error limit
  245. const double dist_err = calcDistance2d(current_pose, data.nearest_pose);
  246. if (dist_err > m_admissible_position_error) {
  247. warn_throttle("Too large position error: %fm > %fm", dist_err, m_admissible_position_error);
  248. return {false, MPCData{}};
  249. }
  250. // check yaw error limit
  251. if (std::fabs(data.yaw_err) > m_admissible_yaw_error_rad) {
  252. warn_throttle("Too large yaw error: %f > %f", data.yaw_err, m_admissible_yaw_error_rad);
  253. return {false, MPCData{}};
  254. }
  255. // check trajectory time length
  256. const double max_prediction_time =
  257. m_param.min_prediction_length / static_cast<double>(m_param.prediction_horizon - 1);
  258. auto end_time = data.nearest_time + m_param.input_delay + m_ctrl_period + max_prediction_time;
  259. if (end_time > traj.relative_time.back()) {
  260. warn_throttle("path is too short for prediction.");
  261. return {false, MPCData{}};
  262. }
  263. return {true, data};
  264. }
  265. std::pair<bool, MPCTrajectory> MPC::resampleMPCTrajectoryByTime(
  266. const double ts, const double prediction_dt, const MPCTrajectory & input) const
  267. {
  268. MPCTrajectory output;
  269. std::vector<double> mpc_time_v;
  270. for (double i = 0; i < static_cast<double>(m_param.prediction_horizon); ++i) {
  271. mpc_time_v.push_back(ts + i * prediction_dt);
  272. }
  273. if (!MPCUtils::linearInterpMPCTrajectory(input.relative_time, input, mpc_time_v, output)) {
  274. warn_throttle("calculateMPC: mpc resample error. stop mpc calculation. check code!");
  275. return {false, {}};
  276. }
  277. return {true, output};
  278. }
  279. VectorXd MPC::getInitialState(const MPCData & data)
  280. {
  281. const int DIM_X = m_vehicle_model_ptr->getDimX();
  282. VectorXd x0 = VectorXd::Zero(DIM_X);
  283. const auto & lat_err = data.lateral_err;
  284. const auto & steer = m_use_steer_prediction ? data.predicted_steer : data.steer;
  285. const auto & yaw_err = data.yaw_err;
  286. const auto vehicle_model = m_vehicle_model_ptr->modelName();
  287. if (vehicle_model == "kinematics") {
  288. x0 << lat_err, yaw_err, steer;
  289. } else if (vehicle_model == "kinematics_no_delay") {
  290. x0 << lat_err, yaw_err;
  291. } else if (vehicle_model == "dynamics") {
  292. double dlat = (lat_err - m_lateral_error_prev) / m_ctrl_period;
  293. double dyaw = (yaw_err - m_yaw_error_prev) / m_ctrl_period;
  294. m_lateral_error_prev = lat_err;
  295. m_yaw_error_prev = yaw_err;
  296. dlat = m_lpf_lateral_error.filter(dlat);
  297. dyaw = m_lpf_yaw_error.filter(dyaw);
  298. x0 << lat_err, dlat, yaw_err, dyaw;
  299. RCLCPP_DEBUG(m_logger, "(before lpf) dot_lat_err = %f, dot_yaw_err = %f", dlat, dyaw);
  300. RCLCPP_DEBUG(m_logger, "(after lpf) dot_lat_err = %f, dot_yaw_err = %f", dlat, dyaw);
  301. } else {
  302. RCLCPP_ERROR(m_logger, "vehicle_model_type is undefined");
  303. }
  304. return x0;
  305. }
  306. std::pair<bool, VectorXd> MPC::updateStateForDelayCompensation(
  307. const MPCTrajectory & traj, const double & start_time, const VectorXd & x0_orig)
  308. {
  309. const int DIM_X = m_vehicle_model_ptr->getDimX();
  310. const int DIM_U = m_vehicle_model_ptr->getDimU();
  311. const int DIM_Y = m_vehicle_model_ptr->getDimY();
  312. MatrixXd Ad(DIM_X, DIM_X);
  313. MatrixXd Bd(DIM_X, DIM_U);
  314. MatrixXd Wd(DIM_X, 1);
  315. MatrixXd Cd(DIM_Y, DIM_X);
  316. MatrixXd x_curr = x0_orig;
  317. double mpc_curr_time = start_time;
  318. for (size_t i = 0; i < m_input_buffer.size(); ++i) {
  319. double k, v = 0.0;
  320. try {
  321. k = interpolation::lerp(traj.relative_time, traj.k, mpc_curr_time);
  322. v = interpolation::lerp(traj.relative_time, traj.vx, mpc_curr_time);
  323. } catch (const std::exception & e) {
  324. RCLCPP_ERROR(m_logger, "mpc resample failed at delay compensation, stop mpc: %s", e.what());
  325. return {false, {}};
  326. }
  327. // get discrete state matrix A, B, C, W
  328. m_vehicle_model_ptr->setVelocity(v);
  329. m_vehicle_model_ptr->setCurvature(k);
  330. m_vehicle_model_ptr->calculateDiscreteMatrix(Ad, Bd, Cd, Wd, m_ctrl_period);
  331. MatrixXd ud = MatrixXd::Zero(DIM_U, 1);
  332. ud(0, 0) = m_input_buffer.at(i); // for steering input delay
  333. x_curr = Ad * x_curr + Bd * ud + Wd;
  334. mpc_curr_time += m_ctrl_period;
  335. }
  336. return {true, x_curr};
  337. }
  338. MPCTrajectory MPC::applyVelocityDynamicsFilter(
  339. const MPCTrajectory & input, const Odometry & current_kinematics) const
  340. {
  341. const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(input);
  342. if (autoware_traj.points.empty()) {
  343. return input;
  344. }
  345. const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
  346. autoware_traj.points, current_kinematics.pose.pose, ego_nearest_dist_threshold,
  347. ego_nearest_yaw_threshold);
  348. MPCTrajectory output = input;
  349. MPCUtils::dynamicSmoothingVelocity(
  350. nearest_seg_idx, current_kinematics.twist.twist.linear.x, m_param.acceleration_limit,
  351. m_param.velocity_time_constant, output);
  352. auto last_point = output.back();
  353. last_point.relative_time += 100.0; // extra time to prevent mpc calc failure due to short time
  354. last_point.vx = 0.0; // stop velocity at a terminal point
  355. output.push_back(last_point);
  356. return output;
  357. }
  358. /*
  359. * predict equation: Xec = Aex * x0 + Bex * Uex + Wex
  360. * cost function: J = Xex' * Qex * Xex + (Uex - Uref)' * R1ex * (Uex - Uref_ex) + Uex' * R2ex * Uex
  361. * Qex = diag([Q,Q,...]), R1ex = diag([R,R,...])
  362. */
  363. MPCMatrix MPC::generateMPCMatrix(
  364. const MPCTrajectory & reference_trajectory, const double prediction_dt)
  365. {
  366. const int N = m_param.prediction_horizon;
  367. const double DT = prediction_dt;
  368. const int DIM_X = m_vehicle_model_ptr->getDimX();
  369. const int DIM_U = m_vehicle_model_ptr->getDimU();
  370. const int DIM_Y = m_vehicle_model_ptr->getDimY();
  371. MPCMatrix m;
  372. m.Aex = MatrixXd::Zero(DIM_X * N, DIM_X);
  373. m.Bex = MatrixXd::Zero(DIM_X * N, DIM_U * N);
  374. m.Wex = MatrixXd::Zero(DIM_X * N, 1);
  375. m.Cex = MatrixXd::Zero(DIM_Y * N, DIM_X * N);
  376. m.Qex = MatrixXd::Zero(DIM_Y * N, DIM_Y * N);
  377. m.R1ex = MatrixXd::Zero(DIM_U * N, DIM_U * N);
  378. m.R2ex = MatrixXd::Zero(DIM_U * N, DIM_U * N);
  379. m.Uref_ex = MatrixXd::Zero(DIM_U * N, 1);
  380. // weight matrix depends on the vehicle model
  381. MatrixXd Q = MatrixXd::Zero(DIM_Y, DIM_Y);
  382. MatrixXd R = MatrixXd::Zero(DIM_U, DIM_U);
  383. MatrixXd Q_adaptive = MatrixXd::Zero(DIM_Y, DIM_Y);
  384. MatrixXd R_adaptive = MatrixXd::Zero(DIM_U, DIM_U);
  385. MatrixXd Ad(DIM_X, DIM_X);
  386. MatrixXd Bd(DIM_X, DIM_U);
  387. MatrixXd Wd(DIM_X, 1);
  388. MatrixXd Cd(DIM_Y, DIM_X);
  389. MatrixXd Uref(DIM_U, 1);
  390. const double sign_vx = m_is_forward_shift ? 1 : -1;
  391. // predict dynamics for N times
  392. for (int i = 0; i < N; ++i) {
  393. const double ref_vx = reference_trajectory.vx.at(i);
  394. const double ref_vx_squared = ref_vx * ref_vx;
  395. const double ref_k = reference_trajectory.k.at(i) * sign_vx;
  396. const double ref_smooth_k = reference_trajectory.smooth_k.at(i) * sign_vx;
  397. // get discrete state matrix A, B, C, W
  398. m_vehicle_model_ptr->setVelocity(ref_vx);
  399. m_vehicle_model_ptr->setCurvature(ref_k);
  400. m_vehicle_model_ptr->calculateDiscreteMatrix(Ad, Bd, Cd, Wd, DT);
  401. Q = MatrixXd::Zero(DIM_Y, DIM_Y);
  402. R = MatrixXd::Zero(DIM_U, DIM_U);
  403. const auto mpc_weight = getWeight(ref_k);
  404. Q(0, 0) = mpc_weight.lat_error;
  405. Q(1, 1) = mpc_weight.heading_error;
  406. R(0, 0) = mpc_weight.steering_input;
  407. Q_adaptive = Q;
  408. R_adaptive = R;
  409. if (i == N - 1) {
  410. Q_adaptive(0, 0) = m_param.nominal_weight.terminal_lat_error;
  411. Q_adaptive(1, 1) = m_param.nominal_weight.terminal_heading_error;
  412. }
  413. Q_adaptive(1, 1) += ref_vx_squared * mpc_weight.heading_error_squared_vel;
  414. R_adaptive(0, 0) += ref_vx_squared * mpc_weight.steering_input_squared_vel;
  415. // update mpc matrix
  416. int idx_x_i = i * DIM_X;
  417. int idx_x_i_prev = (i - 1) * DIM_X;
  418. int idx_u_i = i * DIM_U;
  419. int idx_y_i = i * DIM_Y;
  420. if (i == 0) {
  421. m.Aex.block(0, 0, DIM_X, DIM_X) = Ad;
  422. m.Bex.block(0, 0, DIM_X, DIM_U) = Bd;
  423. m.Wex.block(0, 0, DIM_X, 1) = Wd;
  424. } else {
  425. m.Aex.block(idx_x_i, 0, DIM_X, DIM_X) = Ad * m.Aex.block(idx_x_i_prev, 0, DIM_X, DIM_X);
  426. for (int j = 0; j < i; ++j) {
  427. int idx_u_j = j * DIM_U;
  428. m.Bex.block(idx_x_i, idx_u_j, DIM_X, DIM_U) =
  429. Ad * m.Bex.block(idx_x_i_prev, idx_u_j, DIM_X, DIM_U);
  430. }
  431. m.Wex.block(idx_x_i, 0, DIM_X, 1) = Ad * m.Wex.block(idx_x_i_prev, 0, DIM_X, 1) + Wd;
  432. }
  433. m.Bex.block(idx_x_i, idx_u_i, DIM_X, DIM_U) = Bd;
  434. m.Cex.block(idx_y_i, idx_x_i, DIM_Y, DIM_X) = Cd;
  435. m.Qex.block(idx_y_i, idx_y_i, DIM_Y, DIM_Y) = Q_adaptive;
  436. m.R1ex.block(idx_u_i, idx_u_i, DIM_U, DIM_U) = R_adaptive;
  437. // get reference input (feed-forward)
  438. m_vehicle_model_ptr->setCurvature(ref_smooth_k);
  439. m_vehicle_model_ptr->calculateReferenceInput(Uref);
  440. if (std::fabs(Uref(0, 0)) < tier4_autoware_utils::deg2rad(m_param.zero_ff_steer_deg)) {
  441. Uref(0, 0) = 0.0; // ignore curvature noise
  442. }
  443. m.Uref_ex.block(i * DIM_U, 0, DIM_U, 1) = Uref;
  444. }
  445. // add lateral jerk : weight for (v * {u(i) - u(i-1)} )^2
  446. for (int i = 0; i < N - 1; ++i) {
  447. const double ref_vx = reference_trajectory.vx.at(i);
  448. const double ref_k = reference_trajectory.k.at(i) * sign_vx;
  449. const double j = ref_vx * ref_vx * getWeight(ref_k).lat_jerk / (DT * DT);
  450. const Eigen::Matrix2d J = (Eigen::Matrix2d() << j, -j, -j, j).finished();
  451. m.R2ex.block(i, i, 2, 2) += J;
  452. }
  453. addSteerWeightR(prediction_dt, m.R1ex);
  454. return m;
  455. }
  456. /*
  457. * solve quadratic optimization.
  458. * cost function: J = Xex' * Qex * Xex + (Uex - Uref)' * R1ex * (Uex - Uref_ex) + Uex' * R2ex * Uex
  459. * , Qex = diag([Q,Q,...]), R1ex = diag([R,R,...])
  460. * constraint matrix : lb < U < ub, lbA < A*U < ubA
  461. * current considered constraint
  462. * - steering limit
  463. * - steering rate limit
  464. *
  465. * (1)lb < u < ub && (2)lbA < Au < ubA --> (3)[lb, lbA] < [I, A]u < [ub, ubA]
  466. * (1)lb < u < ub ...
  467. * [-u_lim] < [ u0 ] < [u_lim]
  468. * [-u_lim] < [ u1 ] < [u_lim]
  469. * ~~~
  470. * [-u_lim] < [ uN ] < [u_lim] (*N... DIM_U)
  471. * (2)lbA < Au < ubA ...
  472. * [prev_u0 - au_lim*ctp] < [ u0 ] < [prev_u0 + au_lim*ctp] (*ctp ... ctrl_period)
  473. * [ -au_lim * dt ] < [u1 - u0] < [ au_lim * dt ]
  474. * [ -au_lim * dt ] < [u2 - u1] < [ au_lim * dt ]
  475. * ~~~
  476. * [ -au_lim * dt ] < [uN-uN-1] < [ au_lim * dt ] (*N... DIM_U)
  477. */
  478. std::pair<bool, VectorXd> MPC::executeOptimization(
  479. const MPCMatrix & m, const VectorXd & x0, const double prediction_dt, const MPCTrajectory & traj,
  480. const double current_velocity)
  481. {
  482. VectorXd Uex;
  483. if (!isValid(m)) {
  484. warn_throttle("model matrix is invalid. stop MPC.");
  485. return {false, {}};
  486. }
  487. const int DIM_U_N = m_param.prediction_horizon * m_vehicle_model_ptr->getDimU();
  488. // cost function: 1/2 * Uex' * H * Uex + f' * Uex, H = B' * C' * Q * C * B + R
  489. const MatrixXd CB = m.Cex * m.Bex;
  490. const MatrixXd QCB = m.Qex * CB;
  491. // MatrixXd H = CB.transpose() * QCB + m.R1ex + m.R2ex; // This calculation is heavy. looking for
  492. // a good way. //NOLINT
  493. MatrixXd H = MatrixXd::Zero(DIM_U_N, DIM_U_N);
  494. H.triangularView<Eigen::Upper>() = CB.transpose() * QCB;
  495. H.triangularView<Eigen::Upper>() += m.R1ex + m.R2ex;
  496. H.triangularView<Eigen::Lower>() = H.transpose();
  497. MatrixXd f = (m.Cex * (m.Aex * x0 + m.Wex)).transpose() * QCB - m.Uref_ex.transpose() * m.R1ex;
  498. addSteerWeightF(prediction_dt, f);
  499. MatrixXd A = MatrixXd::Identity(DIM_U_N, DIM_U_N);
  500. for (int i = 1; i < DIM_U_N; i++) {
  501. A(i, i - 1) = -1.0;
  502. }
  503. // steering angle limit
  504. VectorXd lb = VectorXd::Constant(DIM_U_N, -m_steer_lim); // min steering angle
  505. VectorXd ub = VectorXd::Constant(DIM_U_N, m_steer_lim); // max steering angle
  506. // steering angle rate limit
  507. VectorXd steer_rate_limits = calcSteerRateLimitOnTrajectory(traj, current_velocity);
  508. VectorXd ubA = steer_rate_limits * prediction_dt;
  509. VectorXd lbA = -steer_rate_limits * prediction_dt;
  510. ubA(0) = m_raw_steer_cmd_prev + steer_rate_limits(0) * m_ctrl_period;
  511. lbA(0) = m_raw_steer_cmd_prev - steer_rate_limits(0) * m_ctrl_period;
  512. auto t_start = std::chrono::system_clock::now();
  513. bool solve_result = m_qpsolver_ptr->solve(H, f.transpose(), A, lb, ub, lbA, ubA, Uex);
  514. auto t_end = std::chrono::system_clock::now();
  515. if (!solve_result) {
  516. warn_throttle("qp solver error");
  517. return {false, {}};
  518. }
  519. {
  520. auto t = std::chrono::duration_cast<std::chrono::milliseconds>(t_end - t_start).count();
  521. RCLCPP_DEBUG(m_logger, "qp solver calculation time = %ld [ms]", t);
  522. }
  523. if (Uex.array().isNaN().any()) {
  524. warn_throttle("model Uex includes NaN, stop MPC.");
  525. return {false, {}};
  526. }
  527. return {true, Uex};
  528. }
  529. void MPC::addSteerWeightR(const double prediction_dt, MatrixXd & R) const
  530. {
  531. const int N = m_param.prediction_horizon;
  532. const double DT = prediction_dt;
  533. // add steering rate : weight for (u(i) - u(i-1) / dt )^2
  534. {
  535. const double steer_rate_r = m_param.nominal_weight.steer_rate / (DT * DT);
  536. const Eigen::Matrix2d D = steer_rate_r * (Eigen::Matrix2d() << 1.0, -1.0, -1.0, 1.0).finished();
  537. for (int i = 0; i < N - 1; ++i) {
  538. R.block(i, i, 2, 2) += D;
  539. }
  540. if (N > 1) {
  541. // steer rate i = 0
  542. R(0, 0) += m_param.nominal_weight.steer_rate / (m_ctrl_period * m_ctrl_period);
  543. }
  544. }
  545. // add steering acceleration : weight for { (u(i+1) - 2*u(i) + u(i-1)) / dt^2 }^2
  546. {
  547. const double w = m_param.nominal_weight.steer_acc;
  548. const double steer_acc_r = w / std::pow(DT, 4);
  549. const double steer_acc_r_cp1 = w / (std::pow(DT, 3) * m_ctrl_period);
  550. const double steer_acc_r_cp2 = w / (std::pow(DT, 2) * std::pow(m_ctrl_period, 2));
  551. const double steer_acc_r_cp4 = w / std::pow(m_ctrl_period, 4);
  552. const Eigen::Matrix3d D =
  553. steer_acc_r *
  554. (Eigen::Matrix3d() << 1.0, -2.0, 1.0, -2.0, 4.0, -2.0, 1.0, -2.0, 1.0).finished();
  555. for (int i = 1; i < N - 1; ++i) {
  556. R.block(i - 1, i - 1, 3, 3) += D;
  557. }
  558. if (N > 1) {
  559. // steer acc i = 1
  560. R(0, 0) += steer_acc_r * 1.0 + steer_acc_r_cp2 * 1.0 + steer_acc_r_cp1 * 2.0;
  561. R(1, 0) += steer_acc_r * -1.0 + steer_acc_r_cp1 * -1.0;
  562. R(0, 1) += steer_acc_r * -1.0 + steer_acc_r_cp1 * -1.0;
  563. R(1, 1) += steer_acc_r * 1.0;
  564. // steer acc i = 0
  565. R(0, 0) += steer_acc_r_cp4 * 1.0;
  566. }
  567. }
  568. }
  569. void MPC::addSteerWeightF(const double prediction_dt, MatrixXd & f) const
  570. {
  571. if (f.rows() < 2) {
  572. return;
  573. }
  574. const double DT = prediction_dt;
  575. // steer rate for i = 0
  576. f(0, 0) += -2.0 * m_param.nominal_weight.steer_rate / (std::pow(DT, 2)) * 0.5;
  577. // const double steer_acc_r = m_param.weight_steer_acc / std::pow(DT, 4);
  578. const double steer_acc_r_cp1 =
  579. m_param.nominal_weight.steer_acc / (std::pow(DT, 3) * m_ctrl_period);
  580. const double steer_acc_r_cp2 =
  581. m_param.nominal_weight.steer_acc / (std::pow(DT, 2) * std::pow(m_ctrl_period, 2));
  582. const double steer_acc_r_cp4 = m_param.nominal_weight.steer_acc / std::pow(m_ctrl_period, 4);
  583. // steer acc i = 0
  584. f(0, 0) += ((-2.0 * m_raw_steer_cmd_prev + m_raw_steer_cmd_pprev) * steer_acc_r_cp4) * 0.5;
  585. // steer acc for i = 1
  586. f(0, 0) += (-2.0 * m_raw_steer_cmd_prev * (steer_acc_r_cp1 + steer_acc_r_cp2)) * 0.5;
  587. f(0, 1) += (2.0 * m_raw_steer_cmd_prev * steer_acc_r_cp1) * 0.5;
  588. }
  589. double MPC::getPredictionDeltaTime(
  590. const double start_time, const MPCTrajectory & input, const Odometry & current_kinematics) const
  591. {
  592. // Calculate the time min_prediction_length ahead from current_pose
  593. const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(input);
  594. const size_t nearest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints(
  595. autoware_traj.points, current_kinematics.pose.pose, ego_nearest_dist_threshold,
  596. ego_nearest_yaw_threshold);
  597. double sum_dist = 0;
  598. const double target_time = [&]() {
  599. const double t_ext = 100.0; // extra time to prevent mpc calculation failure due to short time
  600. for (size_t i = nearest_idx + 1; i < input.relative_time.size(); i++) {
  601. const double segment_dist = MPCUtils::calcDistance2d(input, i, i - 1);
  602. sum_dist += segment_dist;
  603. if (m_param.min_prediction_length < sum_dist) {
  604. const double prev_sum_dist = sum_dist - segment_dist;
  605. const double ratio = (m_param.min_prediction_length - prev_sum_dist) / segment_dist;
  606. const double relative_time_at_i = i == input.relative_time.size() - 1
  607. ? input.relative_time.at(i) - t_ext
  608. : input.relative_time.at(i);
  609. return input.relative_time.at(i - 1) +
  610. (relative_time_at_i - input.relative_time.at(i - 1)) * ratio;
  611. }
  612. }
  613. return input.relative_time.back() - t_ext;
  614. }();
  615. // Calculate delta time for min_prediction_length
  616. const double dt =
  617. (target_time - start_time) / static_cast<double>(m_param.prediction_horizon - 1);
  618. return std::max(dt, m_param.prediction_dt);
  619. }
  620. double MPC::calcDesiredSteeringRate(
  621. const MPCMatrix & mpc_matrix, const MatrixXd & x0, const MatrixXd & Uex, const double u_filtered,
  622. const float current_steer, const double predict_dt) const
  623. {
  624. if (m_vehicle_model_ptr->modelName() != "kinematics") {
  625. // not supported yet. Use old implementation.
  626. return (u_filtered - current_steer) / predict_dt;
  627. }
  628. // calculate predicted states to get the steering motion
  629. const auto & m = mpc_matrix;
  630. const MatrixXd Xex = m.Aex * x0 + m.Bex * Uex + m.Wex;
  631. const size_t STEER_IDX = 2; // for kinematics model
  632. const auto steer_0 = x0(STEER_IDX, 0);
  633. const auto steer_1 = Xex(STEER_IDX, 0);
  634. const auto steer_rate = (steer_1 - steer_0) / predict_dt;
  635. return steer_rate;
  636. }
  637. VectorXd MPC::calcSteerRateLimitOnTrajectory(
  638. const MPCTrajectory & trajectory, const double current_velocity) const
  639. {
  640. const auto interp = [&](const auto & steer_rate_limit_map, const auto & current) {
  641. std::vector<double> reference, limits;
  642. for (const auto & p : steer_rate_limit_map) {
  643. reference.push_back(p.first);
  644. limits.push_back(p.second);
  645. }
  646. // If the speed is out of range of the reference, apply zero-order hold.
  647. if (current <= reference.front()) {
  648. return limits.front();
  649. }
  650. if (current >= reference.back()) {
  651. return limits.back();
  652. }
  653. // Apply linear interpolation
  654. for (size_t i = 0; i < reference.size() - 1; ++i) {
  655. if (reference.at(i) <= current && current <= reference.at(i + 1)) {
  656. auto ratio =
  657. (current - reference.at(i)) / std::max(reference.at(i + 1) - reference.at(i), 1.0e-5);
  658. ratio = std::clamp(ratio, 0.0, 1.0);
  659. const auto interp = limits.at(i) + ratio * (limits.at(i + 1) - limits.at(i));
  660. return interp;
  661. }
  662. }
  663. std::cerr << "MPC::calcSteerRateLimitOnTrajectory() interpolation logic is broken. Command "
  664. "filter is not working. Please check the code."
  665. << std::endl;
  666. return reference.back();
  667. };
  668. // when the vehicle is stopped, no steering rate limit.
  669. const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01;
  670. if (is_vehicle_stopped) {
  671. return VectorXd::Zero(m_param.prediction_horizon);
  672. }
  673. // calculate steering rate limit
  674. VectorXd steer_rate_limits = VectorXd::Zero(m_param.prediction_horizon);
  675. for (int i = 0; i < m_param.prediction_horizon; ++i) {
  676. const auto limit_by_curvature = interp(m_steer_rate_lim_map_by_curvature, trajectory.k.at(i));
  677. const auto limit_by_velocity = interp(m_steer_rate_lim_map_by_velocity, trajectory.vx.at(i));
  678. steer_rate_limits(i) = std::min(limit_by_curvature, limit_by_velocity);
  679. }
  680. return steer_rate_limits;
  681. }
  682. bool MPC::isValid(const MPCMatrix & m) const
  683. {
  684. if (
  685. m.Aex.array().isNaN().any() || m.Bex.array().isNaN().any() || m.Cex.array().isNaN().any() ||
  686. m.Wex.array().isNaN().any() || m.Qex.array().isNaN().any() || m.R1ex.array().isNaN().any() ||
  687. m.R2ex.array().isNaN().any() || m.Uref_ex.array().isNaN().any()) {
  688. return false;
  689. }
  690. if (
  691. m.Aex.array().isInf().any() || m.Bex.array().isInf().any() || m.Cex.array().isInf().any() ||
  692. m.Wex.array().isInf().any() || m.Qex.array().isInf().any() || m.R1ex.array().isInf().any() ||
  693. m.R2ex.array().isInf().any() || m.Uref_ex.array().isInf().any()) {
  694. return false;
  695. }
  696. return true;
  697. }
  698. } // namespace autoware::motion::control::mpc_lateral_controller