mpc.cpp 47 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134
  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. #include <chrono>
  22. namespace autoware::motion::control::mpc_lateral_controller
  23. {
  24. //using tier4_autoware_utils::calcDistance2d;
  25. //using tier4_autoware_utils::normalizeRadian;
  26. //using tier4_autoware_utils::rad2deg;
  27. //bool MPC::calculateMPC(
  28. // const SteeringReport & current_steer, const Odometry & current_kinematics,
  29. // AckermannLateralCommand & ctrl_cmd, Trajectory & predicted_trajectory,
  30. // Float32MultiArrayStamped & diagnostic)
  31. //{
  32. // // since the reference trajectory does not take into account the current velocity of the ego
  33. // // vehicle, it needs to calculate the trajectory velocity considering the longitudinal dynamics.
  34. // const auto reference_trajectory =
  35. // applyVelocityDynamicsFilter(m_reference_trajectory, current_kinematics);
  36. // // get the necessary data
  37. // const auto [success_data, mpc_data] =
  38. // getData(reference_trajectory, current_steer, current_kinematics);
  39. // if (!success_data) {
  40. // return fail_warn_throttle("fail to get MPC Data. Stop MPC.");
  41. // }
  42. // // calculate initial state of the error dynamics
  43. // const auto x0 = getInitialState(mpc_data);
  44. // // apply time delay compensation to the initial state
  45. // const auto [success_delay, x0_delayed] =
  46. // updateStateForDelayCompensation(reference_trajectory, mpc_data.nearest_time, x0);
  47. // if (!success_delay) {
  48. // return fail_warn_throttle("delay compensation failed. Stop MPC.");
  49. // }
  50. // // resample reference trajectory with mpc sampling time
  51. // const double mpc_start_time = mpc_data.nearest_time + m_param.input_delay;
  52. // const double prediction_dt =
  53. // getPredictionDeltaTime(mpc_start_time, reference_trajectory, current_kinematics);
  54. // const auto [success_resample, mpc_resampled_ref_trajectory] =
  55. // resampleMPCTrajectoryByTime(mpc_start_time, prediction_dt, reference_trajectory);
  56. // if (!success_resample) {
  57. // return fail_warn_throttle("trajectory resampling failed. Stop MPC.");
  58. // }
  59. // // generate mpc matrix : predict equation Xec = Aex * x0 + Bex * Uex + Wex
  60. // const auto mpc_matrix = generateMPCMatrix(mpc_resampled_ref_trajectory, prediction_dt);
  61. // // solve Optimization problem
  62. // const auto [success_opt, Uex] = executeOptimization(
  63. // mpc_matrix, x0_delayed, prediction_dt, mpc_resampled_ref_trajectory,
  64. // current_kinematics.twist.twist.linear.x);
  65. // if (!success_opt) {
  66. // return fail_warn_throttle("optimization failed. Stop MPC.");
  67. // }
  68. // // apply filters for the input limitation and low pass filter
  69. // const double u_saturated = std::clamp(Uex(0), -m_steer_lim, m_steer_lim);
  70. // const double u_filtered = m_lpf_steering_cmd.filter(u_saturated);
  71. // // set control command
  72. // ctrl_cmd.steering_tire_angle = static_cast<float>(u_filtered);
  73. // ctrl_cmd.steering_tire_rotation_rate = static_cast<float>(calcDesiredSteeringRate(
  74. // mpc_matrix, x0_delayed, Uex, u_filtered, current_steer.steering_tire_angle, prediction_dt));
  75. // // save the control command for the steering prediction
  76. // m_steering_predictor->storeSteerCmd(u_filtered);
  77. // // save input to buffer for delay compensation
  78. // m_input_buffer.push_back(ctrl_cmd.steering_tire_angle);
  79. // m_input_buffer.pop_front();
  80. // // save previous input for the mpc rate limit
  81. // m_raw_steer_cmd_pprev = m_raw_steer_cmd_prev;
  82. // m_raw_steer_cmd_prev = Uex(0);
  83. // // calculate predicted trajectory
  84. // predicted_trajectory =
  85. // calcPredictedTrajectory(mpc_resampled_ref_trajectory, mpc_matrix, x0_delayed, Uex);
  86. // // prepare diagnostic message
  87. // diagnostic =
  88. // generateDiagData(reference_trajectory, mpc_data, mpc_matrix, ctrl_cmd, Uex, current_kinematics);
  89. // return true;
  90. //}
  91. bool MPC::calculateMPC(
  92. const iv::ADCSteeringReport & current_steer, const iv::ADCOdometry & current_kinematics,
  93. ADCAckermannLateralCommand & ctrl_cmd, MPCTrajectory & predicted_trajectory
  94. )
  95. {
  96. // since the reference trajectory does not take into account the current velocity of the ego
  97. // vehicle, it needs to calculate the trajectory velocity considering the longitudinal dynamics.
  98. const auto reference_trajectory =
  99. applyVelocityDynamicsFilter(m_reference_trajectory, current_kinematics);
  100. // get the necessary data
  101. const auto [success_data, mpc_data] =
  102. getData(reference_trajectory, current_steer, current_kinematics);
  103. if (!success_data) {
  104. std::cout<<"fail to get MPC Data. Stop MPC."<<std::endl;
  105. return false;
  106. // return fail_warn_throttle("fail to get MPC Data. Stop MPC.");
  107. }
  108. // calculate initial state of the error dynamics
  109. const auto x0 = getInitialState(mpc_data);
  110. // apply time delay compensation to the initial state
  111. const auto [success_delay, x0_delayed] =
  112. updateStateForDelayCompensation(reference_trajectory, mpc_data.nearest_time, x0);
  113. if (!success_delay) {
  114. std::cout<<"delay compensation failed. Stop MPC."<<std::endl;
  115. return false;
  116. // return fail_warn_throttle("delay compensation failed. Stop MPC.");
  117. }
  118. // resample reference trajectory with mpc sampling time
  119. const double mpc_start_time = mpc_data.nearest_time + m_param.input_delay;
  120. const double prediction_dt =
  121. getPredictionDeltaTime(mpc_start_time, reference_trajectory, current_kinematics);
  122. const auto [success_resample, mpc_resampled_ref_trajectory] =
  123. resampleMPCTrajectoryByTime(mpc_start_time, prediction_dt, reference_trajectory);
  124. if (!success_resample) {
  125. std::cout<<"trajectory resampling failed. Stop MPC."<<std::endl;
  126. return false;
  127. // return fail_warn_throttle("trajectory resampling failed. Stop MPC.");
  128. }
  129. // generate mpc matrix : predict equation Xec = Aex * x0 + Bex * Uex + Wex
  130. const auto mpc_matrix = generateMPCMatrix(mpc_resampled_ref_trajectory, prediction_dt);
  131. // solve Optimization problem
  132. const auto [success_opt, Uex] = executeOptimization(
  133. mpc_matrix, x0_delayed, prediction_dt, mpc_resampled_ref_trajectory,
  134. current_kinematics.twist.linear_x);
  135. if (!success_opt) {
  136. std::cout<<"optimization failed. Stop MPC."<<std::endl;
  137. return false;
  138. // return fail_warn_throttle("optimization failed. Stop MPC.");
  139. }
  140. // apply filters for the input limitation and low pass filter
  141. const double u_saturated = std::clamp(Uex(0), -m_steer_lim, m_steer_lim);
  142. const double u_filtered = m_lpf_steering_cmd.filter(u_saturated);
  143. // set control command
  144. ctrl_cmd.steering_tire_angle = static_cast<float>(u_filtered);
  145. ctrl_cmd.steering_tire_rotation_rate = static_cast<float>(calcDesiredSteeringRate(
  146. mpc_matrix, x0_delayed, Uex, u_filtered, current_steer.steering_tire_angle, prediction_dt));
  147. // save the control command for the steering prediction
  148. m_steering_predictor->storeSteerCmd(u_filtered);
  149. // save input to buffer for delay compensation
  150. m_input_buffer.push_back(ctrl_cmd.steering_tire_angle);
  151. m_input_buffer.pop_front();
  152. // save previous input for the mpc rate limit
  153. m_raw_steer_cmd_pprev = m_raw_steer_cmd_prev;
  154. m_raw_steer_cmd_prev = Uex(0);
  155. // calculate predicted trajectory
  156. predicted_trajectory =
  157. calcPredictedTrajectory(mpc_resampled_ref_trajectory, mpc_matrix, x0_delayed, Uex);
  158. // prepare diagnostic message
  159. // diagnostic =
  160. // generateDiagData(reference_trajectory, mpc_data, mpc_matrix, ctrl_cmd, Uex, current_kinematics);
  161. return true;
  162. }
  163. //Trajectory MPC::calcPredictedTrajectory(
  164. // const MPCTrajectory & mpc_resampled_ref_trajectory, const MPCMatrix & mpc_matrix,
  165. // const VectorXd & x0_delayed, const VectorXd & Uex) const
  166. //{
  167. // const VectorXd Xex = mpc_matrix.Aex * x0_delayed + mpc_matrix.Bex * Uex + mpc_matrix.Wex;
  168. // MPCTrajectory mpc_predicted_traj;
  169. // const auto & traj = mpc_resampled_ref_trajectory;
  170. // for (int i = 0; i < m_param.prediction_horizon; ++i) {
  171. // const int DIM_X = m_vehicle_model_ptr->getDimX();
  172. // const double lat_error = Xex(i * DIM_X);
  173. // const double yaw_error = Xex(i * DIM_X + 1);
  174. // const double x = traj.x.at(i) - std::sin(traj.yaw.at(i)) * lat_error;
  175. // const double y = traj.y.at(i) + std::cos(traj.yaw.at(i)) * lat_error;
  176. // const double z = traj.z.at(i);
  177. // const double yaw = traj.yaw.at(i) + yaw_error;
  178. // const double vx = traj.vx.at(i);
  179. // const double k = traj.k.at(i);
  180. // const double smooth_k = traj.smooth_k.at(i);
  181. // const double relative_time = traj.relative_time.at(i);
  182. // mpc_predicted_traj.push_back(x, y, z, yaw, vx, k, smooth_k, relative_time);
  183. // }
  184. // return MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj);
  185. //}
  186. MPCTrajectory MPC::calcPredictedTrajectory(
  187. const MPCTrajectory & mpc_resampled_ref_trajectory, const MPCMatrix & mpc_matrix,
  188. const VectorXd & x0_delayed, const VectorXd & Uex) const
  189. {
  190. const VectorXd Xex = mpc_matrix.Aex * x0_delayed + mpc_matrix.Bex * Uex + mpc_matrix.Wex;
  191. MPCTrajectory mpc_predicted_traj;
  192. const auto & traj = mpc_resampled_ref_trajectory;
  193. for (int i = 0; i < m_param.prediction_horizon; ++i) {
  194. const int DIM_X = m_vehicle_model_ptr->getDimX();
  195. const double lat_error = Xex(i * DIM_X);
  196. const double yaw_error = Xex(i * DIM_X + 1);
  197. const double x = traj.x.at(i) - std::sin(traj.yaw.at(i)) * lat_error;
  198. const double y = traj.y.at(i) + std::cos(traj.yaw.at(i)) * lat_error;
  199. const double z = traj.z.at(i);
  200. const double yaw = traj.yaw.at(i) + yaw_error;
  201. const double vx = traj.vx.at(i);
  202. const double k = traj.k.at(i);
  203. const double smooth_k = traj.smooth_k.at(i);
  204. const double relative_time = traj.relative_time.at(i);
  205. mpc_predicted_traj.push_back(x, y, z, yaw, vx, k, smooth_k, relative_time);
  206. }
  207. return mpc_predicted_traj;
  208. // return MPCUtils::convertToAutowareTrajectory(mpc_predicted_traj);
  209. }
  210. //Float32MultiArrayStamped MPC::generateDiagData(
  211. // const MPCTrajectory & reference_trajectory, const MPCData & mpc_data,
  212. // const MPCMatrix & mpc_matrix, const AckermannLateralCommand & ctrl_cmd, const VectorXd & Uex,
  213. // const Odometry & current_kinematics) const
  214. //{
  215. // Float32MultiArrayStamped diagnostic;
  216. // // prepare diagnostic message
  217. // const double nearest_k = reference_trajectory.k.at(mpc_data.nearest_idx);
  218. // const double nearest_smooth_k = reference_trajectory.smooth_k.at(mpc_data.nearest_idx);
  219. // const double wb = m_vehicle_model_ptr->getWheelbase();
  220. // const double current_velocity = current_kinematics.twist.twist.linear.x;
  221. // const double wz_predicted = current_velocity * std::tan(mpc_data.predicted_steer) / wb;
  222. // const double wz_measured = current_velocity * std::tan(mpc_data.steer) / wb;
  223. // const double wz_command = current_velocity * std::tan(ctrl_cmd.steering_tire_angle) / wb;
  224. // typedef decltype(diagnostic.data)::value_type DiagnosticValueType;
  225. // const auto append_diag = [&](const auto & val) -> void {
  226. // diagnostic.data.push_back(static_cast<DiagnosticValueType>(val));
  227. // };
  228. // append_diag(ctrl_cmd.steering_tire_angle); // [0] final steering command (MPC + LPF)
  229. // append_diag(Uex(0)); // [1] mpc calculation result
  230. // append_diag(mpc_matrix.Uref_ex(0)); // [2] feed-forward steering value
  231. // append_diag(std::atan(nearest_smooth_k * wb)); // [3] feed-forward steering value raw
  232. // append_diag(mpc_data.steer); // [4] current steering angle
  233. // append_diag(mpc_data.lateral_err); // [5] lateral error
  234. // append_diag(tf2::getYaw(current_kinematics.pose.pose.orientation)); // [6] current_pose yaw
  235. // append_diag(tf2::getYaw(mpc_data.nearest_pose.orientation)); // [7] nearest_pose yaw
  236. // append_diag(mpc_data.yaw_err); // [8] yaw error
  237. // append_diag(reference_trajectory.vx.at(mpc_data.nearest_idx)); // [9] reference velocity
  238. // append_diag(current_velocity); // [10] measured velocity
  239. // append_diag(wz_command); // [11] angular velocity from steer command
  240. // append_diag(wz_measured); // [12] angular velocity from measured steer
  241. // append_diag(current_velocity * nearest_smooth_k); // [13] angular velocity from path curvature
  242. // append_diag(nearest_smooth_k); // [14] nearest path curvature (used for feed-forward)
  243. // append_diag(nearest_k); // [15] nearest path curvature (not smoothed)
  244. // append_diag(mpc_data.predicted_steer); // [16] predicted steer
  245. // append_diag(wz_predicted); // [17] angular velocity from predicted steer
  246. // return diagnostic;
  247. //}
  248. //void MPC::setReferenceTrajectory(
  249. // const Trajectory & trajectory_msg, const TrajectoryFilteringParam & param,
  250. // const Odometry & current_kinematics)
  251. //{
  252. // const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
  253. // trajectory_msg.points, current_kinematics.pose.pose, ego_nearest_dist_threshold,
  254. // ego_nearest_yaw_threshold);
  255. // const double ego_offset_to_segment = motion_utils::calcLongitudinalOffsetToSegment(
  256. // trajectory_msg.points, nearest_seg_idx, current_kinematics.pose.pose.position);
  257. // const auto mpc_traj_raw = MPCUtils::convertToMPCTrajectory(trajectory_msg);
  258. // // resampling
  259. // const auto [success_resample, mpc_traj_resampled] = MPCUtils::resampleMPCTrajectoryByDistance(
  260. // mpc_traj_raw, param.traj_resample_dist, nearest_seg_idx, ego_offset_to_segment);
  261. // if (!success_resample) {
  262. // warn_throttle("[setReferenceTrajectory] spline error when resampling by distance");
  263. // return;
  264. // }
  265. // const auto is_forward_shift =
  266. // motion_utils::isDrivingForward(mpc_traj_resampled.toTrajectoryPoints());
  267. // // if driving direction is unknown, use previous value
  268. // m_is_forward_shift = is_forward_shift ? is_forward_shift.get() : m_is_forward_shift;
  269. // // path smoothing
  270. // MPCTrajectory mpc_traj_smoothed = mpc_traj_resampled; // smooth filtered trajectory
  271. // const int mpc_traj_resampled_size = static_cast<int>(mpc_traj_resampled.size());
  272. // if (
  273. // param.enable_path_smoothing && mpc_traj_resampled_size > 2 * param.path_filter_moving_ave_num) {
  274. // using MoveAverageFilter::filt_vector;
  275. // if (
  276. // !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.x) ||
  277. // !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.y) ||
  278. // !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.yaw) ||
  279. // !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.vx)) {
  280. // RCLCPP_DEBUG(m_logger, "path callback: filtering error. stop filtering.");
  281. // mpc_traj_smoothed = mpc_traj_resampled;
  282. // }
  283. // }
  284. // /*
  285. // * Extend terminal points
  286. // * Note: The current MPC does not properly take into account the attitude angle at the end of the
  287. // * path. By extending the end of the path in the attitude direction, the MPC can consider the
  288. // * attitude angle well, resulting in improved control performance. If the trajectory is
  289. // * well-defined considering the end point attitude angle, this feature is not necessary.
  290. // */
  291. // if (param.extend_trajectory_for_end_yaw_control) {
  292. // MPCUtils::extendTrajectoryInYawDirection(
  293. // mpc_traj_raw.yaw.back(), param.traj_resample_dist, m_is_forward_shift, mpc_traj_smoothed);
  294. // }
  295. // // calculate yaw angle
  296. // MPCUtils::calcTrajectoryYawFromXY(mpc_traj_smoothed, m_is_forward_shift);
  297. // MPCUtils::convertEulerAngleToMonotonic(mpc_traj_smoothed.yaw);
  298. // // calculate curvature
  299. // MPCUtils::calcTrajectoryCurvature(
  300. // param.curvature_smoothing_num_traj, param.curvature_smoothing_num_ref_steer, mpc_traj_smoothed);
  301. // // stop velocity at a terminal point
  302. // mpc_traj_smoothed.vx.back() = 0.0;
  303. // // add a extra point on back with extended time to make the mpc stable.
  304. // auto last_point = mpc_traj_smoothed.back();
  305. // last_point.relative_time += 100.0; // extra time to prevent mpc calc failure due to short time
  306. // last_point.vx = 0.0; // stop velocity at a terminal point
  307. // mpc_traj_smoothed.push_back(last_point);
  308. // if (!mpc_traj_smoothed.size()) {
  309. // RCLCPP_DEBUG(m_logger, "path callback: trajectory size is undesired.");
  310. // return;
  311. // }
  312. // m_reference_trajectory = mpc_traj_smoothed;
  313. //}
  314. void MPC::setReferenceTrajectory(
  315. const MPCTrajectory & trajectory_msg, const TrajectoryFilteringParam & param,
  316. const iv::ADCOdometry & current_kinematics)
  317. {
  318. const size_t nearest_seg_idx = MPCUtils::findFirstNearestSegmentIndexWithSoftConstraints(
  319. trajectory_msg, current_kinematics.pose, ego_nearest_dist_threshold,
  320. ego_nearest_yaw_threshold);
  321. const double ego_offset_to_segment = MPCUtils::calcLongitudinalOffsetToSegment(
  322. trajectory_msg, nearest_seg_idx, current_kinematics.pose.position);
  323. const auto mpc_traj_raw = trajectory_msg;// MPCUtils::convertToMPCTrajectory(trajectory_msg);
  324. // resampling
  325. const auto [success_resample, mpc_traj_resampled] = MPCUtils::resampleMPCTrajectoryByDistance(
  326. mpc_traj_raw, param.traj_resample_dist, nearest_seg_idx, ego_offset_to_segment);
  327. if (!success_resample) {
  328. std::cout<<"[setReferenceTrajectory] spline error when resampling by distance"<<std::endl;
  329. // warn_throttle("[setReferenceTrajectory] spline error when resampling by distance");
  330. return;
  331. }
  332. const auto is_forward_shift =
  333. MPCUtils::isDrivingForward(mpc_traj_resampled);
  334. // if driving direction is unknown, use previous value
  335. m_is_forward_shift = is_forward_shift;// ? is_forward_shift.get() : m_is_forward_shift;
  336. // path smoothing
  337. MPCTrajectory mpc_traj_smoothed = mpc_traj_resampled; // smooth filtered trajectory
  338. const int mpc_traj_resampled_size = static_cast<int>(mpc_traj_resampled.size());
  339. if (
  340. param.enable_path_smoothing && mpc_traj_resampled_size > 2 * param.path_filter_moving_ave_num) {
  341. using MoveAverageFilter::filt_vector;
  342. if (
  343. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.x) ||
  344. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.y) ||
  345. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.yaw) ||
  346. !filt_vector(param.path_filter_moving_ave_num, mpc_traj_smoothed.vx)) {
  347. std::cout<<"path callback: filtering error. stop filtering."<<std::endl;
  348. // RCLCPP_DEBUG(m_logger, "path callback: filtering error. stop filtering.");
  349. mpc_traj_smoothed = mpc_traj_resampled;
  350. }
  351. }
  352. /*
  353. * Extend terminal points
  354. * Note: The current MPC does not properly take into account the attitude angle at the end of the
  355. * path. By extending the end of the path in the attitude direction, the MPC can consider the
  356. * attitude angle well, resulting in improved control performance. If the trajectory is
  357. * well-defined considering the end point attitude angle, this feature is not necessary.
  358. */
  359. if (param.extend_trajectory_for_end_yaw_control) {
  360. MPCUtils::extendTrajectoryInYawDirection(
  361. mpc_traj_raw.yaw.back(), param.traj_resample_dist, m_is_forward_shift, mpc_traj_smoothed);
  362. }
  363. // calculate yaw angle
  364. MPCUtils::calcTrajectoryYawFromXY(mpc_traj_smoothed, m_is_forward_shift);
  365. MPCUtils::convertEulerAngleToMonotonic(mpc_traj_smoothed.yaw);
  366. // calculate curvature
  367. MPCUtils::calcTrajectoryCurvature(
  368. param.curvature_smoothing_num_traj, param.curvature_smoothing_num_ref_steer, mpc_traj_smoothed);
  369. // stop velocity at a terminal point
  370. mpc_traj_smoothed.vx.back() = 0.0;
  371. // add a extra point on back with extended time to make the mpc stable.
  372. auto last_point = mpc_traj_smoothed.back();
  373. last_point.relative_time += 100.0; // extra time to prevent mpc calc failure due to short time
  374. last_point.vx = 0.0; // stop velocity at a terminal point
  375. mpc_traj_smoothed.push_back(last_point);
  376. if (!mpc_traj_smoothed.size()) {
  377. std::cout<<"path callback: trajectory size is undesired."<<std::endl;
  378. // RCLCPP_DEBUG(m_logger, "path callback: trajectory size is undesired.");
  379. return;
  380. }
  381. m_reference_trajectory = mpc_traj_smoothed;
  382. }
  383. //void MPC::resetPrevResult(const SteeringReport & current_steer)
  384. //{
  385. // // Consider limit. The prev value larger than limitation brakes the optimization constraint and
  386. // // results in optimization failure.
  387. // const float steer_lim_f = static_cast<float>(m_steer_lim);
  388. // m_raw_steer_cmd_prev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f);
  389. // m_raw_steer_cmd_pprev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f);
  390. //}
  391. void MPC::resetPrevResult(const iv::ADCSteeringReport & current_steer)
  392. {
  393. // Consider limit. The prev value larger than limitation brakes the optimization constraint and
  394. // results in optimization failure.
  395. const float steer_lim_f = static_cast<float>(m_steer_lim); //
  396. m_raw_steer_cmd_prev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f);
  397. m_raw_steer_cmd_pprev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f);
  398. }
  399. //std::pair<bool, MPCData> MPC::getData(
  400. // const MPCTrajectory & traj, const SteeringReport & current_steer,
  401. // const Odometry & current_kinematics)
  402. //{
  403. // const auto current_pose = current_kinematics.pose.pose;
  404. // MPCData data;
  405. // if (!MPCUtils::calcNearestPoseInterp(
  406. // traj, current_pose, &(data.nearest_pose), &(data.nearest_idx), &(data.nearest_time),
  407. // ego_nearest_dist_threshold, ego_nearest_yaw_threshold)) {
  408. // warn_throttle("calculateMPC: error in calculating nearest pose. stop mpc.");
  409. // return {false, MPCData{}};
  410. // }
  411. // // get data
  412. // data.steer = static_cast<double>(current_steer.steering_tire_angle);
  413. // data.lateral_err = MPCUtils::calcLateralError(current_pose, data.nearest_pose);
  414. // data.yaw_err = normalizeRadian(
  415. // tf2::getYaw(current_pose.orientation) - tf2::getYaw(data.nearest_pose.orientation));
  416. // // get predicted steer
  417. // data.predicted_steer = m_steering_predictor->calcSteerPrediction();
  418. // // check error limit
  419. // const double dist_err = calcDistance2d(current_pose, data.nearest_pose);
  420. // if (dist_err > m_admissible_position_error) {
  421. // warn_throttle("Too large position error: %fm > %fm", dist_err, m_admissible_position_error);
  422. // return {false, MPCData{}};
  423. // }
  424. // // check yaw error limit
  425. // if (std::fabs(data.yaw_err) > m_admissible_yaw_error_rad) {
  426. // warn_throttle("Too large yaw error: %f > %f", data.yaw_err, m_admissible_yaw_error_rad);
  427. // return {false, MPCData{}};
  428. // }
  429. // // check trajectory time length
  430. // const double max_prediction_time =
  431. // m_param.min_prediction_length / static_cast<double>(m_param.prediction_horizon - 1);
  432. // auto end_time = data.nearest_time + m_param.input_delay + m_ctrl_period + max_prediction_time;
  433. // if (end_time > traj.relative_time.back()) {
  434. // warn_throttle("path is too short for prediction.");
  435. // return {false, MPCData{}};
  436. // }
  437. // return {true, data};
  438. //}
  439. std::pair<bool, MPCData> MPC::getData(
  440. const MPCTrajectory & traj, const iv::ADCSteeringReport & current_steer,
  441. const iv::ADCOdometry & current_kinematics)
  442. {
  443. const auto current_pose = current_kinematics.pose;
  444. MPCData data;
  445. if (!MPCUtils::calcNearestPoseInterp(
  446. traj, current_pose, &(data.nearest_pose), &(data.nearest_idx), &(data.nearest_time),
  447. ego_nearest_dist_threshold, ego_nearest_yaw_threshold)) {
  448. std::cout<<"calculateMPC: error in calculating nearest pose. stop mpc."<<std::endl;
  449. // warn_throttle("calculateMPC: error in calculating nearest pose. stop mpc.");
  450. return {false, MPCData{}};
  451. }
  452. // get data
  453. data.steer = static_cast<double>(current_steer.steering_tire_angle);
  454. data.lateral_err = MPCUtils::calcLateralError(current_pose, data.nearest_pose);
  455. data.yaw_err = MPCUtils::ADCnormalizeRadian(
  456. MPCUtils::ADCgetYaw(current_pose.orientation) - MPCUtils::ADCgetYaw(data.nearest_pose.orientation));
  457. // get predicted steer
  458. data.predicted_steer = m_steering_predictor->calcSteerPrediction();
  459. // check error limit
  460. const double dist_err = MPCUtils::ADCcalcDistance2d(current_pose.position, data.nearest_pose.position);
  461. if (dist_err > m_admissible_position_error) {
  462. printf("Too large position error: %fm > %fm", dist_err, m_admissible_position_error);
  463. // warn_throttle("Too large position error: %fm > %fm", dist_err, m_admissible_position_error);
  464. return {false, MPCData{}};
  465. }
  466. // check yaw error limit
  467. if (std::fabs(data.yaw_err) > m_admissible_yaw_error_rad) {
  468. printf("Too large yaw error: %f > %f", data.yaw_err, m_admissible_yaw_error_rad);
  469. // warn_throttle("Too large yaw error: %f > %f", data.yaw_err, m_admissible_yaw_error_rad);
  470. return {false, MPCData{}};
  471. }
  472. // check trajectory time length
  473. const double max_prediction_time =
  474. m_param.min_prediction_length / static_cast<double>(m_param.prediction_horizon - 1);
  475. auto end_time = data.nearest_time + m_param.input_delay + m_ctrl_period + max_prediction_time;
  476. if (end_time > traj.relative_time.back()) {
  477. printf("path is too short for prediction.");
  478. // warn_throttle("path is too short for prediction.");
  479. return {false, MPCData{}};
  480. }
  481. return {true, data};
  482. }
  483. std::pair<bool, MPCTrajectory> MPC::resampleMPCTrajectoryByTime(
  484. const double ts, const double prediction_dt, const MPCTrajectory & input) const
  485. {
  486. MPCTrajectory output;
  487. std::vector<double> mpc_time_v;
  488. for (double i = 0; i < static_cast<double>(m_param.prediction_horizon); ++i) {
  489. mpc_time_v.push_back(ts + i * prediction_dt);
  490. }
  491. if (!MPCUtils::linearInterpMPCTrajectory(input.relative_time, input, mpc_time_v, output)) {
  492. printf("calculateMPC: mpc resample error. stop mpc calculation. check code!");
  493. // warn_throttle("calculateMPC: mpc resample error. stop mpc calculation. check code!");
  494. return {false, {}};
  495. }
  496. return {true, output};
  497. }
  498. VectorXd MPC::getInitialState(const MPCData & data)
  499. {
  500. const int DIM_X = m_vehicle_model_ptr->getDimX();
  501. VectorXd x0 = VectorXd::Zero(DIM_X);
  502. const auto & lat_err = data.lateral_err;
  503. const auto & steer = m_use_steer_prediction ? data.predicted_steer : data.steer;
  504. const auto & yaw_err = data.yaw_err;
  505. const auto vehicle_model = m_vehicle_model_ptr->modelName();
  506. if (vehicle_model == "kinematics") {
  507. x0 << lat_err, yaw_err, steer;
  508. } else if (vehicle_model == "kinematics_no_delay") {
  509. x0 << lat_err, yaw_err;
  510. } else if (vehicle_model == "dynamics") {
  511. double dlat = (lat_err - m_lateral_error_prev) / m_ctrl_period;
  512. double dyaw = (yaw_err - m_yaw_error_prev) / m_ctrl_period;
  513. m_lateral_error_prev = lat_err;
  514. m_yaw_error_prev = yaw_err;
  515. dlat = m_lpf_lateral_error.filter(dlat);
  516. dyaw = m_lpf_yaw_error.filter(dyaw);
  517. x0 << lat_err, dlat, yaw_err, dyaw;
  518. std::cout<<"(before lpf) dot_lat_err = "<<dlat<<", dot_yaw_err = "<<dyaw<<std::endl;
  519. std::cout<<"(after lpf) dot_lat_err = "<<dlat<<", dot_yaw_err = "<<dyaw<<std::endl;
  520. // RCLCPP_DEBUG(m_logger, "(before lpf) dot_lat_err = %f, dot_yaw_err = %f", dlat, dyaw);
  521. // RCLCPP_DEBUG(m_logger, "(after lpf) dot_lat_err = %f, dot_yaw_err = %f", dlat, dyaw);
  522. } else {
  523. std::cout<<"vehicle_model_type is undefined"<<std::endl;
  524. // RCLCPP_ERROR(m_logger, "vehicle_model_type is undefined");
  525. }
  526. return x0;
  527. }
  528. std::pair<bool, VectorXd> MPC::updateStateForDelayCompensation(
  529. const MPCTrajectory & traj, const double & start_time, const VectorXd & x0_orig)
  530. {
  531. const int DIM_X = m_vehicle_model_ptr->getDimX();
  532. const int DIM_U = m_vehicle_model_ptr->getDimU();
  533. const int DIM_Y = m_vehicle_model_ptr->getDimY();
  534. MatrixXd Ad(DIM_X, DIM_X);
  535. MatrixXd Bd(DIM_X, DIM_U);
  536. MatrixXd Wd(DIM_X, 1);
  537. MatrixXd Cd(DIM_Y, DIM_X);
  538. MatrixXd x_curr = x0_orig;
  539. double mpc_curr_time = start_time;
  540. for (size_t i = 0; i < m_input_buffer.size(); ++i) {
  541. double k, v = 0.0;
  542. try {
  543. k = interpolation::lerp(traj.relative_time, traj.k, mpc_curr_time);
  544. v = interpolation::lerp(traj.relative_time, traj.vx, mpc_curr_time);
  545. } catch (const std::exception & e) {
  546. std::cout<<"mpc resample failed at delay compensation, stop mpc: "<<e.what()<<std::endl;
  547. // RCLCPP_ERROR(m_logger, "mpc resample failed at delay compensation, stop mpc: %s", e.what());
  548. return {false, {}};
  549. }
  550. // get discrete state matrix A, B, C, W
  551. m_vehicle_model_ptr->setVelocity(v);
  552. m_vehicle_model_ptr->setCurvature(k);
  553. m_vehicle_model_ptr->calculateDiscreteMatrix(Ad, Bd, Cd, Wd, m_ctrl_period);
  554. MatrixXd ud = MatrixXd::Zero(DIM_U, 1);
  555. ud(0, 0) = m_input_buffer.at(i); // for steering input delay
  556. x_curr = Ad * x_curr + Bd * ud + Wd;
  557. mpc_curr_time += m_ctrl_period;
  558. }
  559. return {true, x_curr};
  560. }
  561. //MPCTrajectory MPC::applyVelocityDynamicsFilter(
  562. // const MPCTrajectory & input, const Odometry & current_kinematics) const
  563. //{
  564. // const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(input);
  565. // if (autoware_traj.points.empty()) {
  566. // return input;
  567. // }
  568. // const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
  569. // autoware_traj.points, current_kinematics.pose.pose, ego_nearest_dist_threshold,
  570. // ego_nearest_yaw_threshold);
  571. // MPCTrajectory output = input;
  572. // MPCUtils::dynamicSmoothingVelocity(
  573. // nearest_seg_idx, current_kinematics.twist.twist.linear.x, m_param.acceleration_limit,
  574. // m_param.velocity_time_constant, output);
  575. // auto last_point = output.back();
  576. // last_point.relative_time += 100.0; // extra time to prevent mpc calc failure due to short time
  577. // last_point.vx = 0.0; // stop velocity at a terminal point
  578. // output.push_back(last_point);
  579. // return output;
  580. //}
  581. MPCTrajectory MPC::applyVelocityDynamicsFilter(
  582. const MPCTrajectory & trajectory, const iv::ADCOdometry & current_kinematics) const
  583. {
  584. // const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(input);
  585. if (trajectory.size() == 0) {
  586. return trajectory;
  587. }
  588. const size_t nearest_seg_idx = MPCUtils::findFirstNearestSegmentIndexWithSoftConstraints(
  589. trajectory, current_kinematics.pose, ego_nearest_dist_threshold,
  590. ego_nearest_yaw_threshold);
  591. MPCTrajectory output = trajectory;
  592. MPCUtils::dynamicSmoothingVelocity(
  593. nearest_seg_idx, current_kinematics.twist.linear_x, m_param.acceleration_limit,
  594. m_param.velocity_time_constant, output);
  595. auto last_point = output.back();
  596. last_point.relative_time += 100.0; // extra time to prevent mpc calc failure due to short time
  597. last_point.vx = 0.0; // stop velocity at a terminal point
  598. output.push_back(last_point);
  599. return output;
  600. }
  601. /*
  602. * predict equation: Xec = Aex * x0 + Bex * Uex + Wex
  603. * cost function: J = Xex' * Qex * Xex + (Uex - Uref)' * R1ex * (Uex - Uref_ex) + Uex' * R2ex * Uex
  604. * Qex = diag([Q,Q,...]), R1ex = diag([R,R,...])
  605. */
  606. MPCMatrix MPC::generateMPCMatrix(
  607. const MPCTrajectory & reference_trajectory, const double prediction_dt)
  608. {
  609. const int N = m_param.prediction_horizon;
  610. const double DT = prediction_dt;
  611. const int DIM_X = m_vehicle_model_ptr->getDimX();
  612. const int DIM_U = m_vehicle_model_ptr->getDimU();
  613. const int DIM_Y = m_vehicle_model_ptr->getDimY();
  614. MPCMatrix m;
  615. m.Aex = MatrixXd::Zero(DIM_X * N, DIM_X);
  616. m.Bex = MatrixXd::Zero(DIM_X * N, DIM_U * N);
  617. m.Wex = MatrixXd::Zero(DIM_X * N, 1);
  618. m.Cex = MatrixXd::Zero(DIM_Y * N, DIM_X * N);
  619. m.Qex = MatrixXd::Zero(DIM_Y * N, DIM_Y * N);
  620. m.R1ex = MatrixXd::Zero(DIM_U * N, DIM_U * N);
  621. m.R2ex = MatrixXd::Zero(DIM_U * N, DIM_U * N);
  622. m.Uref_ex = MatrixXd::Zero(DIM_U * N, 1);
  623. // weight matrix depends on the vehicle model
  624. MatrixXd Q = MatrixXd::Zero(DIM_Y, DIM_Y);
  625. MatrixXd R = MatrixXd::Zero(DIM_U, DIM_U);
  626. MatrixXd Q_adaptive = MatrixXd::Zero(DIM_Y, DIM_Y);
  627. MatrixXd R_adaptive = MatrixXd::Zero(DIM_U, DIM_U);
  628. MatrixXd Ad(DIM_X, DIM_X);
  629. MatrixXd Bd(DIM_X, DIM_U);
  630. MatrixXd Wd(DIM_X, 1);
  631. MatrixXd Cd(DIM_Y, DIM_X);
  632. MatrixXd Uref(DIM_U, 1);
  633. const double sign_vx = m_is_forward_shift ? 1 : -1;
  634. // predict dynamics for N times
  635. for (int i = 0; i < N; ++i) {
  636. const double ref_vx = reference_trajectory.vx.at(i);
  637. const double ref_vx_squared = ref_vx * ref_vx;
  638. const double ref_k = reference_trajectory.k.at(i) * sign_vx;
  639. const double ref_smooth_k = reference_trajectory.smooth_k.at(i) * sign_vx;
  640. // get discrete state matrix A, B, C, W
  641. m_vehicle_model_ptr->setVelocity(ref_vx);
  642. m_vehicle_model_ptr->setCurvature(ref_k);
  643. m_vehicle_model_ptr->calculateDiscreteMatrix(Ad, Bd, Cd, Wd, DT);
  644. Q = MatrixXd::Zero(DIM_Y, DIM_Y);
  645. R = MatrixXd::Zero(DIM_U, DIM_U);
  646. const auto mpc_weight = getWeight(ref_k);
  647. Q(0, 0) = mpc_weight.lat_error;
  648. Q(1, 1) = mpc_weight.heading_error;
  649. R(0, 0) = mpc_weight.steering_input;
  650. Q_adaptive = Q;
  651. R_adaptive = R;
  652. if (i == N - 1) {
  653. Q_adaptive(0, 0) = m_param.nominal_weight.terminal_lat_error;
  654. Q_adaptive(1, 1) = m_param.nominal_weight.terminal_heading_error;
  655. }
  656. Q_adaptive(1, 1) += ref_vx_squared * mpc_weight.heading_error_squared_vel;
  657. R_adaptive(0, 0) += ref_vx_squared * mpc_weight.steering_input_squared_vel;
  658. // update mpc matrix
  659. int idx_x_i = i * DIM_X;
  660. int idx_x_i_prev = (i - 1) * DIM_X;
  661. int idx_u_i = i * DIM_U;
  662. int idx_y_i = i * DIM_Y;
  663. if (i == 0) {
  664. m.Aex.block(0, 0, DIM_X, DIM_X) = Ad;
  665. m.Bex.block(0, 0, DIM_X, DIM_U) = Bd;
  666. m.Wex.block(0, 0, DIM_X, 1) = Wd;
  667. } else {
  668. m.Aex.block(idx_x_i, 0, DIM_X, DIM_X) = Ad * m.Aex.block(idx_x_i_prev, 0, DIM_X, DIM_X);
  669. for (int j = 0; j < i; ++j) {
  670. int idx_u_j = j * DIM_U;
  671. m.Bex.block(idx_x_i, idx_u_j, DIM_X, DIM_U) =
  672. Ad * m.Bex.block(idx_x_i_prev, idx_u_j, DIM_X, DIM_U);
  673. }
  674. m.Wex.block(idx_x_i, 0, DIM_X, 1) = Ad * m.Wex.block(idx_x_i_prev, 0, DIM_X, 1) + Wd;
  675. }
  676. m.Bex.block(idx_x_i, idx_u_i, DIM_X, DIM_U) = Bd;
  677. m.Cex.block(idx_y_i, idx_x_i, DIM_Y, DIM_X) = Cd;
  678. m.Qex.block(idx_y_i, idx_y_i, DIM_Y, DIM_Y) = Q_adaptive;
  679. m.R1ex.block(idx_u_i, idx_u_i, DIM_U, DIM_U) = R_adaptive;
  680. // get reference input (feed-forward)
  681. m_vehicle_model_ptr->setCurvature(ref_smooth_k);
  682. m_vehicle_model_ptr->calculateReferenceInput(Uref);
  683. if (std::fabs(Uref(0, 0)) < MPCUtils::deg2rad(m_param.zero_ff_steer_deg)) {
  684. Uref(0, 0) = 0.0; // ignore curvature noise
  685. }
  686. m.Uref_ex.block(i * DIM_U, 0, DIM_U, 1) = Uref;
  687. }
  688. // add lateral jerk : weight for (v * {u(i) - u(i-1)} )^2
  689. for (int i = 0; i < N - 1; ++i) {
  690. const double ref_vx = reference_trajectory.vx.at(i);
  691. const double ref_k = reference_trajectory.k.at(i) * sign_vx;
  692. const double j = ref_vx * ref_vx * getWeight(ref_k).lat_jerk / (DT * DT);
  693. const Eigen::Matrix2d J = (Eigen::Matrix2d() << j, -j, -j, j).finished();
  694. m.R2ex.block(i, i, 2, 2) += J;
  695. }
  696. addSteerWeightR(prediction_dt, m.R1ex);
  697. return m;
  698. }
  699. /*
  700. * solve quadratic optimization.
  701. * cost function: J = Xex' * Qex * Xex + (Uex - Uref)' * R1ex * (Uex - Uref_ex) + Uex' * R2ex * Uex
  702. * , Qex = diag([Q,Q,...]), R1ex = diag([R,R,...])
  703. * constraint matrix : lb < U < ub, lbA < A*U < ubA
  704. * current considered constraint
  705. * - steering limit
  706. * - steering rate limit
  707. *
  708. * (1)lb < u < ub && (2)lbA < Au < ubA --> (3)[lb, lbA] < [I, A]u < [ub, ubA]
  709. * (1)lb < u < ub ...
  710. * [-u_lim] < [ u0 ] < [u_lim]
  711. * [-u_lim] < [ u1 ] < [u_lim]
  712. * ~~~
  713. * [-u_lim] < [ uN ] < [u_lim] (*N... DIM_U)
  714. * (2)lbA < Au < ubA ...
  715. * [prev_u0 - au_lim*ctp] < [ u0 ] < [prev_u0 + au_lim*ctp] (*ctp ... ctrl_period)
  716. * [ -au_lim * dt ] < [u1 - u0] < [ au_lim * dt ]
  717. * [ -au_lim * dt ] < [u2 - u1] < [ au_lim * dt ]
  718. * ~~~
  719. * [ -au_lim * dt ] < [uN-uN-1] < [ au_lim * dt ] (*N... DIM_U)
  720. */
  721. std::pair<bool, VectorXd> MPC::executeOptimization(
  722. const MPCMatrix & m, const VectorXd & x0, const double prediction_dt, const MPCTrajectory & traj,
  723. const double current_velocity)
  724. {
  725. VectorXd Uex;
  726. if (!isValid(m)) {
  727. printf("model matrix is invalid. stop MPC.");
  728. // warn_throttle("model matrix is invalid. stop MPC.");
  729. return {false, {}};
  730. }
  731. const int DIM_U_N = m_param.prediction_horizon * m_vehicle_model_ptr->getDimU();
  732. // cost function: 1/2 * Uex' * H * Uex + f' * Uex, H = B' * C' * Q * C * B + R
  733. const MatrixXd CB = m.Cex * m.Bex;
  734. const MatrixXd QCB = m.Qex * CB;
  735. // MatrixXd H = CB.transpose() * QCB + m.R1ex + m.R2ex; // This calculation is heavy. looking for
  736. // a good way. //NOLINT
  737. MatrixXd H = MatrixXd::Zero(DIM_U_N, DIM_U_N);
  738. H.triangularView<Eigen::Upper>() = CB.transpose() * QCB;
  739. H.triangularView<Eigen::Upper>() += m.R1ex + m.R2ex;
  740. H.triangularView<Eigen::Lower>() = H.transpose();
  741. MatrixXd f = (m.Cex * (m.Aex * x0 + m.Wex)).transpose() * QCB - m.Uref_ex.transpose() * m.R1ex;
  742. addSteerWeightF(prediction_dt, f);
  743. MatrixXd A = MatrixXd::Identity(DIM_U_N, DIM_U_N);
  744. for (int i = 1; i < DIM_U_N; i++) {
  745. A(i, i - 1) = -1.0;
  746. }
  747. // steering angle limit
  748. VectorXd lb = VectorXd::Constant(DIM_U_N, -m_steer_lim); // min steering angle
  749. VectorXd ub = VectorXd::Constant(DIM_U_N, m_steer_lim); // max steering angle
  750. // steering angle rate limit
  751. VectorXd steer_rate_limits = calcSteerRateLimitOnTrajectory(traj, current_velocity);
  752. VectorXd ubA = steer_rate_limits * prediction_dt;
  753. VectorXd lbA = -steer_rate_limits * prediction_dt;
  754. ubA(0) = m_raw_steer_cmd_prev + steer_rate_limits(0) * m_ctrl_period;
  755. lbA(0) = m_raw_steer_cmd_prev - steer_rate_limits(0) * m_ctrl_period;
  756. auto t_start = std::chrono::system_clock::now();
  757. bool solve_result = m_qpsolver_ptr->solve(H, f.transpose(), A, lb, ub, lbA, ubA, Uex);
  758. auto t_end = std::chrono::system_clock::now();
  759. if (!solve_result) {
  760. printf("qp solver error");
  761. // warn_throttle("qp solver error");
  762. return {false, {}};
  763. }
  764. {
  765. auto t = std::chrono::duration_cast<std::chrono::milliseconds>(t_end - t_start).count();
  766. std::cout<<"qp solver calculation time = "<<t<<"[ms]";
  767. // RCLCPP_DEBUG(m_logger, "qp solver calculation time = %ld [ms]", t);
  768. }
  769. if (Uex.array().isNaN().any()) {
  770. printf("model Uex includes NaN, stop MPC.");
  771. // warn_throttle("model Uex includes NaN, stop MPC.");
  772. return {false, {}};
  773. }
  774. return {true, Uex};
  775. }
  776. void MPC::addSteerWeightR(const double prediction_dt, MatrixXd & R) const
  777. {
  778. const int N = m_param.prediction_horizon;
  779. const double DT = prediction_dt;
  780. // add steering rate : weight for (u(i) - u(i-1) / dt )^2
  781. {
  782. const double steer_rate_r = m_param.nominal_weight.steer_rate / (DT * DT);
  783. const Eigen::Matrix2d D = steer_rate_r * (Eigen::Matrix2d() << 1.0, -1.0, -1.0, 1.0).finished();
  784. for (int i = 0; i < N - 1; ++i) {
  785. R.block(i, i, 2, 2) += D;
  786. }
  787. if (N > 1) {
  788. // steer rate i = 0
  789. R(0, 0) += m_param.nominal_weight.steer_rate / (m_ctrl_period * m_ctrl_period);
  790. }
  791. }
  792. // add steering acceleration : weight for { (u(i+1) - 2*u(i) + u(i-1)) / dt^2 }^2
  793. {
  794. const double w = m_param.nominal_weight.steer_acc;
  795. const double steer_acc_r = w / std::pow(DT, 4);
  796. const double steer_acc_r_cp1 = w / (std::pow(DT, 3) * m_ctrl_period);
  797. const double steer_acc_r_cp2 = w / (std::pow(DT, 2) * std::pow(m_ctrl_period, 2));
  798. const double steer_acc_r_cp4 = w / std::pow(m_ctrl_period, 4);
  799. const Eigen::Matrix3d D =
  800. steer_acc_r *
  801. (Eigen::Matrix3d() << 1.0, -2.0, 1.0, -2.0, 4.0, -2.0, 1.0, -2.0, 1.0).finished();
  802. for (int i = 1; i < N - 1; ++i) {
  803. R.block(i - 1, i - 1, 3, 3) += D;
  804. }
  805. if (N > 1) {
  806. // steer acc i = 1
  807. R(0, 0) += steer_acc_r * 1.0 + steer_acc_r_cp2 * 1.0 + steer_acc_r_cp1 * 2.0;
  808. R(1, 0) += steer_acc_r * -1.0 + steer_acc_r_cp1 * -1.0;
  809. R(0, 1) += steer_acc_r * -1.0 + steer_acc_r_cp1 * -1.0;
  810. R(1, 1) += steer_acc_r * 1.0;
  811. // steer acc i = 0
  812. R(0, 0) += steer_acc_r_cp4 * 1.0;
  813. }
  814. }
  815. }
  816. void MPC::addSteerWeightF(const double prediction_dt, MatrixXd & f) const
  817. {
  818. if (f.rows() < 2) {
  819. return;
  820. }
  821. const double DT = prediction_dt;
  822. // steer rate for i = 0
  823. f(0, 0) += -2.0 * m_param.nominal_weight.steer_rate / (std::pow(DT, 2)) * 0.5;
  824. // const double steer_acc_r = m_param.weight_steer_acc / std::pow(DT, 4);
  825. const double steer_acc_r_cp1 =
  826. m_param.nominal_weight.steer_acc / (std::pow(DT, 3) * m_ctrl_period);
  827. const double steer_acc_r_cp2 =
  828. m_param.nominal_weight.steer_acc / (std::pow(DT, 2) * std::pow(m_ctrl_period, 2));
  829. const double steer_acc_r_cp4 = m_param.nominal_weight.steer_acc / std::pow(m_ctrl_period, 4);
  830. // steer acc i = 0
  831. f(0, 0) += ((-2.0 * m_raw_steer_cmd_prev + m_raw_steer_cmd_pprev) * steer_acc_r_cp4) * 0.5;
  832. // steer acc for i = 1
  833. f(0, 0) += (-2.0 * m_raw_steer_cmd_prev * (steer_acc_r_cp1 + steer_acc_r_cp2)) * 0.5;
  834. f(0, 1) += (2.0 * m_raw_steer_cmd_prev * steer_acc_r_cp1) * 0.5;
  835. }
  836. //double MPC::getPredictionDeltaTime(
  837. // const double start_time, const MPCTrajectory & input, const Odometry & current_kinematics) const
  838. //{
  839. // // Calculate the time min_prediction_length ahead from current_pose
  840. // const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(input);
  841. // const size_t nearest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints(
  842. // autoware_traj.points, current_kinematics.pose.pose, ego_nearest_dist_threshold,
  843. // ego_nearest_yaw_threshold);
  844. // double sum_dist = 0;
  845. // const double target_time = [&]() {
  846. // const double t_ext = 100.0; // extra time to prevent mpc calculation failure due to short time
  847. // for (size_t i = nearest_idx + 1; i < input.relative_time.size(); i++) {
  848. // const double segment_dist = MPCUtils::calcDistance2d(input, i, i - 1);
  849. // sum_dist += segment_dist;
  850. // if (m_param.min_prediction_length < sum_dist) {
  851. // const double prev_sum_dist = sum_dist - segment_dist;
  852. // const double ratio = (m_param.min_prediction_length - prev_sum_dist) / segment_dist;
  853. // const double relative_time_at_i = i == input.relative_time.size() - 1
  854. // ? input.relative_time.at(i) - t_ext
  855. // : input.relative_time.at(i);
  856. // return input.relative_time.at(i - 1) +
  857. // (relative_time_at_i - input.relative_time.at(i - 1)) * ratio;
  858. // }
  859. // }
  860. // return input.relative_time.back() - t_ext;
  861. // }();
  862. // // Calculate delta time for min_prediction_length
  863. // const double dt =
  864. // (target_time - start_time) / static_cast<double>(m_param.prediction_horizon - 1);
  865. // return std::max(dt, m_param.prediction_dt);
  866. //}
  867. double MPC::getPredictionDeltaTime(
  868. const double start_time, const MPCTrajectory & input,
  869. const iv::ADCOdometry & current_kinematics) const
  870. {
  871. // Calculate the time min_prediction_length ahead from current_pose
  872. const size_t nearest_idx = MPCUtils::findFirstNearestIndexWithSoftConstraints(
  873. input, current_kinematics.pose, ego_nearest_dist_threshold,
  874. ego_nearest_yaw_threshold);
  875. double sum_dist = 0;
  876. const double target_time = [&]() {
  877. const double t_ext = 100.0; // extra time to prevent mpc calculation failure due to short time
  878. for (size_t i = nearest_idx + 1; i < input.relative_time.size(); i++) {
  879. const double segment_dist = MPCUtils::calcDistance2d(input, i, i - 1);
  880. sum_dist += segment_dist;
  881. if (m_param.min_prediction_length < sum_dist) {
  882. const double prev_sum_dist = sum_dist - segment_dist;
  883. const double ratio = (m_param.min_prediction_length - prev_sum_dist) / segment_dist;
  884. const double relative_time_at_i = i == input.relative_time.size() - 1
  885. ? input.relative_time.at(i) - t_ext
  886. : input.relative_time.at(i);
  887. return input.relative_time.at(i - 1) +
  888. (relative_time_at_i - input.relative_time.at(i - 1)) * ratio;
  889. }
  890. }
  891. return input.relative_time.back() - t_ext;
  892. }();
  893. // Calculate delta time for min_prediction_length
  894. const double dt =
  895. (target_time - start_time) / static_cast<double>(m_param.prediction_horizon - 1);
  896. return std::max(dt, m_param.prediction_dt);
  897. }
  898. double MPC::calcDesiredSteeringRate(
  899. const MPCMatrix & mpc_matrix, const MatrixXd & x0, const MatrixXd & Uex, const double u_filtered,
  900. const float current_steer, const double predict_dt) const
  901. {
  902. if (m_vehicle_model_ptr->modelName() != "kinematics") {
  903. // not supported yet. Use old implementation.
  904. return (u_filtered - current_steer) / predict_dt;
  905. }
  906. // calculate predicted states to get the steering motion
  907. const auto & m = mpc_matrix;
  908. const MatrixXd Xex = m.Aex * x0 + m.Bex * Uex + m.Wex;
  909. const size_t STEER_IDX = 2; // for kinematics model
  910. const auto steer_0 = x0(STEER_IDX, 0);
  911. const auto steer_1 = Xex(STEER_IDX, 0);
  912. const auto steer_rate = (steer_1 - steer_0) / predict_dt;
  913. return steer_rate;
  914. }
  915. VectorXd MPC::calcSteerRateLimitOnTrajectory(
  916. const MPCTrajectory & trajectory, const double current_velocity) const
  917. {
  918. const auto interp = [&](const auto & steer_rate_limit_map, const auto & current) {
  919. std::vector<double> reference, limits;
  920. for (const auto & p : steer_rate_limit_map) {
  921. reference.push_back(p.first);
  922. limits.push_back(p.second);
  923. }
  924. // If the speed is out of range of the reference, apply zero-order hold.
  925. if (current <= reference.front()) {
  926. return limits.front();
  927. }
  928. if (current >= reference.back()) {
  929. return limits.back();
  930. }
  931. // Apply linear interpolation
  932. for (size_t i = 0; i < reference.size() - 1; ++i) {
  933. if (reference.at(i) <= current && current <= reference.at(i + 1)) {
  934. auto ratio =
  935. (current - reference.at(i)) / std::max(reference.at(i + 1) - reference.at(i), 1.0e-5);
  936. ratio = std::clamp(ratio, 0.0, 1.0);
  937. const auto interp = limits.at(i) + ratio * (limits.at(i + 1) - limits.at(i));
  938. return interp;
  939. }
  940. }
  941. std::cerr << "MPC::calcSteerRateLimitOnTrajectory() interpolation logic is broken. Command "
  942. "filter is not working. Please check the code."
  943. << std::endl;
  944. return reference.back();
  945. };
  946. // when the vehicle is stopped, no steering rate limit.
  947. const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01;
  948. if (is_vehicle_stopped) {
  949. return VectorXd::Zero(m_param.prediction_horizon);
  950. }
  951. // calculate steering rate limit
  952. VectorXd steer_rate_limits = VectorXd::Zero(m_param.prediction_horizon);
  953. for (int i = 0; i < m_param.prediction_horizon; ++i) {
  954. const auto limit_by_curvature = interp(m_steer_rate_lim_map_by_curvature, trajectory.k.at(i));
  955. const auto limit_by_velocity = interp(m_steer_rate_lim_map_by_velocity, trajectory.vx.at(i));
  956. steer_rate_limits(i) = std::min(limit_by_curvature, limit_by_velocity);
  957. }
  958. return steer_rate_limits;
  959. }
  960. bool MPC::isValid(const MPCMatrix & m) const
  961. {
  962. if (
  963. m.Aex.array().isNaN().any() || m.Bex.array().isNaN().any() || m.Cex.array().isNaN().any() ||
  964. m.Wex.array().isNaN().any() || m.Qex.array().isNaN().any() || m.R1ex.array().isNaN().any() ||
  965. m.R2ex.array().isNaN().any() || m.Uref_ex.array().isNaN().any()) {
  966. return false;
  967. }
  968. if (
  969. m.Aex.array().isInf().any() || m.Bex.array().isInf().any() || m.Cex.array().isInf().any() ||
  970. m.Wex.array().isInf().any() || m.Qex.array().isInf().any() || m.R1ex.array().isInf().any() ||
  971. m.R2ex.array().isInf().any() || m.Uref_ex.array().isInf().any()) {
  972. return false;
  973. }
  974. return true;
  975. }
  976. } // namespace autoware::motion::control::mpc_lateral_controller