mpc_lateral_controller.cpp 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755
  1. // Copyright 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_lateral_controller.hpp"
  15. #include "motion_utils/trajectory/trajectory.hpp"
  16. #include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp"
  17. #include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp"
  18. #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp"
  19. #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp"
  20. #include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp"
  21. #include "tf2/utils.h"
  22. #include "tf2_ros/create_timer_ros.h"
  23. #include "vehicle_info_util/vehicle_info_util.hpp"
  24. #include <algorithm>
  25. #include <deque>
  26. #include <limits>
  27. #include <memory>
  28. #include <string>
  29. #include <utility>
  30. #include <vector>
  31. namespace autoware::motion::control::mpc_lateral_controller
  32. {
  33. //MpcLateralController::MpcLateralController(rclcpp::Node & node)
  34. //: clock_(node.get_clock()), logger_(node.get_logger().get_child("lateral_controller"))
  35. //{
  36. // const auto dp_int = [&](const std::string & s) { return node.declare_parameter<int>(s); };
  37. // const auto dp_bool = [&](const std::string & s) { return node.declare_parameter<bool>(s); };
  38. // const auto dp_double = [&](const std::string & s) { return node.declare_parameter<double>(s); };
  39. // m_mpc.m_ctrl_period = node.get_parameter("ctrl_period").as_double();
  40. // auto & p_filt = m_trajectory_filtering_param;
  41. // p_filt.enable_path_smoothing = dp_bool("enable_path_smoothing");
  42. // p_filt.path_filter_moving_ave_num = dp_int("path_filter_moving_ave_num");
  43. // p_filt.curvature_smoothing_num_traj = dp_int("curvature_smoothing_num_traj");
  44. // p_filt.curvature_smoothing_num_ref_steer = dp_int("curvature_smoothing_num_ref_steer");
  45. // p_filt.traj_resample_dist = dp_double("traj_resample_dist");
  46. // p_filt.extend_trajectory_for_end_yaw_control = dp_bool("extend_trajectory_for_end_yaw_control");
  47. // m_mpc.m_admissible_position_error = dp_double("admissible_position_error");
  48. // m_mpc.m_admissible_yaw_error_rad = dp_double("admissible_yaw_error_rad");
  49. // m_mpc.m_use_steer_prediction = dp_bool("use_steer_prediction");
  50. // m_mpc.m_param.steer_tau = dp_double("vehicle_model_steer_tau");
  51. // /* stop state parameters */
  52. // m_stop_state_entry_ego_speed = dp_double("stop_state_entry_ego_speed");
  53. // m_stop_state_entry_target_speed = dp_double("stop_state_entry_target_speed");
  54. // m_converged_steer_rad = dp_double("converged_steer_rad");
  55. // m_keep_steer_control_until_converged = dp_bool("keep_steer_control_until_converged");
  56. // m_new_traj_duration_time = dp_double("new_traj_duration_time"); // [s]
  57. // m_new_traj_end_dist = dp_double("new_traj_end_dist"); // [m]
  58. // m_mpc_converged_threshold_rps = dp_double("mpc_converged_threshold_rps"); // [rad/s]
  59. // /* mpc parameters */
  60. // const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
  61. // const double wheelbase = vehicle_info.wheel_base_m;
  62. // constexpr double deg2rad = static_cast<double>(M_PI) / 180.0;
  63. // m_mpc.m_steer_lim = vehicle_info.max_steer_angle_rad;
  64. // // steer rate limit depending on curvature
  65. // const auto steer_rate_lim_dps_list_by_curvature =
  66. // node.declare_parameter<std::vector<double>>("steer_rate_lim_dps_list_by_curvature");
  67. // const auto curvature_list_for_steer_rate_lim =
  68. // node.declare_parameter<std::vector<double>>("curvature_list_for_steer_rate_lim");
  69. // for (size_t i = 0; i < steer_rate_lim_dps_list_by_curvature.size(); ++i) {
  70. // m_mpc.m_steer_rate_lim_map_by_curvature.emplace_back(
  71. // curvature_list_for_steer_rate_lim.at(i),
  72. // steer_rate_lim_dps_list_by_curvature.at(i) * deg2rad);
  73. // }
  74. // // steer rate limit depending on velocity
  75. // const auto steer_rate_lim_dps_list_by_velocity =
  76. // node.declare_parameter<std::vector<double>>("steer_rate_lim_dps_list_by_velocity");
  77. // const auto velocity_list_for_steer_rate_lim =
  78. // node.declare_parameter<std::vector<double>>("velocity_list_for_steer_rate_lim");
  79. // for (size_t i = 0; i < steer_rate_lim_dps_list_by_velocity.size(); ++i) {
  80. // m_mpc.m_steer_rate_lim_map_by_velocity.emplace_back(
  81. // velocity_list_for_steer_rate_lim.at(i), steer_rate_lim_dps_list_by_velocity.at(i) * deg2rad);
  82. // }
  83. // /* vehicle model setup */
  84. // auto vehicle_model_ptr =
  85. // createVehicleModel(wheelbase, m_mpc.m_steer_lim, m_mpc.m_param.steer_tau, node);
  86. // m_mpc.setVehicleModel(vehicle_model_ptr);
  87. // /* QP solver setup */
  88. // m_mpc.setVehicleModel(vehicle_model_ptr);
  89. // auto qpsolver_ptr = createQPSolverInterface(node);
  90. // m_mpc.setQPSolver(qpsolver_ptr);
  91. // /* delay compensation */
  92. // {
  93. // const double delay_tmp = dp_double("input_delay");
  94. // const double delay_step = std::round(delay_tmp / m_mpc.m_ctrl_period);
  95. // m_mpc.m_param.input_delay = delay_step * m_mpc.m_ctrl_period;
  96. // m_mpc.m_input_buffer = std::deque<double>(static_cast<size_t>(delay_step), 0.0);
  97. // }
  98. // /* steering offset compensation */
  99. // enable_auto_steering_offset_removal_ =
  100. // dp_bool("steering_offset.enable_auto_steering_offset_removal");
  101. // steering_offset_ = createSteerOffsetEstimator(wheelbase, node);
  102. // /* initialize low-pass filter */
  103. // {
  104. // const double steering_lpf_cutoff_hz = dp_double("steering_lpf_cutoff_hz");
  105. // const double error_deriv_lpf_cutoff_hz = dp_double("error_deriv_lpf_cutoff_hz");
  106. // m_mpc.initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz);
  107. // }
  108. // // ego nearest index search
  109. // const auto check_and_get_param = [&](const auto & param) {
  110. // return node.has_parameter(param) ? node.get_parameter(param).as_double() : dp_double(param);
  111. // };
  112. // m_ego_nearest_dist_threshold = check_and_get_param("ego_nearest_dist_threshold");
  113. // m_ego_nearest_yaw_threshold = check_and_get_param("ego_nearest_yaw_threshold");
  114. // m_mpc.ego_nearest_dist_threshold = m_ego_nearest_dist_threshold;
  115. // m_mpc.ego_nearest_yaw_threshold = m_ego_nearest_yaw_threshold;
  116. // m_pub_predicted_traj = node.create_publisher<Trajectory>("~/output/predicted_trajectory", 1);
  117. // m_pub_debug_values =
  118. // node.create_publisher<Float32MultiArrayStamped>("~/output/lateral_diagnostic", 1);
  119. // m_pub_steer_offset = node.create_publisher<Float32Stamped>("~/output/estimated_steer_offset", 1);
  120. // declareMPCparameters(node);
  121. // /* get parameter updates */
  122. // using std::placeholders::_1;
  123. // m_set_param_res =
  124. // node.add_on_set_parameters_callback(std::bind(&MpcLateralController::paramCallback, this, _1));
  125. // m_mpc.initializeSteeringPredictor();
  126. // m_mpc.setLogger(logger_);
  127. // m_mpc.setClock(clock_);
  128. //}
  129. MpcLateralController::MpcLateralController()
  130. {
  131. iv::xmlparam::Xmlparam xp("./mpc.xml");
  132. const auto dp_int = [&](const std::string & s) { return xp.GetParam(s,1); };
  133. const auto dp_bool = [&](const std::string & s) { return xp.GetParam(s,false); };
  134. const auto dp_double = [&](const std::string & s) { return xp.GetParam(s,1.0); };
  135. m_mpc.m_ctrl_period = xp.GetParam("ctrl_period",1.0);
  136. // m_mpc.m_ctrl_period = node.get_parameter("ctrl_period").as_double();
  137. auto & p_filt = m_trajectory_filtering_param;
  138. p_filt.enable_path_smoothing = dp_bool("enable_path_smoothing");
  139. p_filt.path_filter_moving_ave_num = dp_int("path_filter_moving_ave_num");
  140. p_filt.curvature_smoothing_num_traj = dp_int("curvature_smoothing_num_traj");
  141. p_filt.curvature_smoothing_num_ref_steer = dp_int("curvature_smoothing_num_ref_steer");
  142. p_filt.traj_resample_dist = dp_double("traj_resample_dist");
  143. p_filt.extend_trajectory_for_end_yaw_control = dp_bool("extend_trajectory_for_end_yaw_control");
  144. m_mpc.m_admissible_position_error = dp_double("admissible_position_error");
  145. m_mpc.m_admissible_yaw_error_rad = dp_double("admissible_yaw_error_rad");
  146. m_mpc.m_use_steer_prediction = dp_bool("use_steer_prediction");
  147. m_mpc.m_param.steer_tau = dp_double("vehicle_model_steer_tau");
  148. /* stop state parameters */
  149. m_stop_state_entry_ego_speed = dp_double("stop_state_entry_ego_speed");
  150. m_stop_state_entry_target_speed = dp_double("stop_state_entry_target_speed");
  151. m_converged_steer_rad = dp_double("converged_steer_rad");
  152. m_keep_steer_control_until_converged = dp_bool("keep_steer_control_until_converged");
  153. m_new_traj_duration_time = dp_double("new_traj_duration_time"); // [s]
  154. m_new_traj_end_dist = dp_double("new_traj_end_dist"); // [m]
  155. m_mpc_converged_threshold_rps = dp_double("mpc_converged_threshold_rps"); // [rad/s]
  156. /* mpc parameters */
  157. // const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
  158. const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(xp).getVehicleInfo();
  159. const double wheelbase = vehicle_info.wheel_base_m;
  160. constexpr double deg2rad = static_cast<double>(M_PI) / 180.0;
  161. m_mpc.m_steer_lim = vehicle_info.max_steer_angle_rad;
  162. // steer rate limit depending on curvature
  163. const auto steer_rate_lim_dps_list_by_curvature =
  164. node.declare_parameter<std::vector<double>>("steer_rate_lim_dps_list_by_curvature");
  165. const auto curvature_list_for_steer_rate_lim =
  166. node.declare_parameter<std::vector<double>>("curvature_list_for_steer_rate_lim");
  167. for (size_t i = 0; i < steer_rate_lim_dps_list_by_curvature.size(); ++i) {
  168. m_mpc.m_steer_rate_lim_map_by_curvature.emplace_back(
  169. curvature_list_for_steer_rate_lim.at(i),
  170. steer_rate_lim_dps_list_by_curvature.at(i) * deg2rad);
  171. }
  172. // steer rate limit depending on velocity
  173. const auto steer_rate_lim_dps_list_by_velocity =
  174. node.declare_parameter<std::vector<double>>("steer_rate_lim_dps_list_by_velocity");
  175. const auto velocity_list_for_steer_rate_lim =
  176. node.declare_parameter<std::vector<double>>("velocity_list_for_steer_rate_lim");
  177. for (size_t i = 0; i < steer_rate_lim_dps_list_by_velocity.size(); ++i) {
  178. m_mpc.m_steer_rate_lim_map_by_velocity.emplace_back(
  179. velocity_list_for_steer_rate_lim.at(i), steer_rate_lim_dps_list_by_velocity.at(i) * deg2rad);
  180. }
  181. /* vehicle model setup */
  182. auto vehicle_model_ptr =
  183. createVehicleModel(wheelbase, m_mpc.m_steer_lim, m_mpc.m_param.steer_tau, node);
  184. m_mpc.setVehicleModel(vehicle_model_ptr);
  185. /* QP solver setup */
  186. m_mpc.setVehicleModel(vehicle_model_ptr);
  187. auto qpsolver_ptr = createQPSolverInterface(node);
  188. m_mpc.setQPSolver(qpsolver_ptr);
  189. /* delay compensation */
  190. {
  191. const double delay_tmp = dp_double("input_delay");
  192. const double delay_step = std::round(delay_tmp / m_mpc.m_ctrl_period);
  193. m_mpc.m_param.input_delay = delay_step * m_mpc.m_ctrl_period;
  194. m_mpc.m_input_buffer = std::deque<double>(static_cast<size_t>(delay_step), 0.0);
  195. }
  196. /* steering offset compensation */
  197. enable_auto_steering_offset_removal_ =
  198. dp_bool("steering_offset.enable_auto_steering_offset_removal");
  199. steering_offset_ = createSteerOffsetEstimator(wheelbase, node);
  200. /* initialize low-pass filter */
  201. {
  202. const double steering_lpf_cutoff_hz = dp_double("steering_lpf_cutoff_hz");
  203. const double error_deriv_lpf_cutoff_hz = dp_double("error_deriv_lpf_cutoff_hz");
  204. m_mpc.initializeLowPassFilters(steering_lpf_cutoff_hz, error_deriv_lpf_cutoff_hz);
  205. }
  206. // ego nearest index search
  207. const auto check_and_get_param = [&](const auto & param) {
  208. return node.has_parameter(param) ? node.get_parameter(param).as_double() : dp_double(param);
  209. };
  210. m_ego_nearest_dist_threshold = check_and_get_param("ego_nearest_dist_threshold");
  211. m_ego_nearest_yaw_threshold = check_and_get_param("ego_nearest_yaw_threshold");
  212. m_mpc.ego_nearest_dist_threshold = m_ego_nearest_dist_threshold;
  213. m_mpc.ego_nearest_yaw_threshold = m_ego_nearest_yaw_threshold;
  214. m_pub_predicted_traj = node.create_publisher<Trajectory>("~/output/predicted_trajectory", 1);
  215. m_pub_debug_values =
  216. node.create_publisher<Float32MultiArrayStamped>("~/output/lateral_diagnostic", 1);
  217. m_pub_steer_offset = node.create_publisher<Float32Stamped>("~/output/estimated_steer_offset", 1);
  218. declareMPCparameters(node);
  219. /* get parameter updates */
  220. using std::placeholders::_1;
  221. m_set_param_res =
  222. node.add_on_set_parameters_callback(std::bind(&MpcLateralController::paramCallback, this, _1));
  223. m_mpc.initializeSteeringPredictor();
  224. m_mpc.setLogger(logger_);
  225. m_mpc.setClock(clock_);
  226. }
  227. MpcLateralController::~MpcLateralController()
  228. {
  229. }
  230. std::shared_ptr<VehicleModelInterface> MpcLateralController::createVehicleModel(
  231. const double wheelbase, const double steer_lim, const double steer_tau, rclcpp::Node & node)
  232. {
  233. std::shared_ptr<VehicleModelInterface> vehicle_model_ptr;
  234. const std::string vehicle_model_type = node.declare_parameter<std::string>("vehicle_model_type");
  235. if (vehicle_model_type == "kinematics") {
  236. vehicle_model_ptr = std::make_shared<KinematicsBicycleModel>(wheelbase, steer_lim, steer_tau);
  237. return vehicle_model_ptr;
  238. }
  239. if (vehicle_model_type == "kinematics_no_delay") {
  240. vehicle_model_ptr = std::make_shared<KinematicsBicycleModelNoDelay>(wheelbase, steer_lim);
  241. return vehicle_model_ptr;
  242. }
  243. if (vehicle_model_type == "dynamics") {
  244. const double mass_fl = node.declare_parameter<double>("vehicle.mass_fl");
  245. const double mass_fr = node.declare_parameter<double>("vehicle.mass_fr");
  246. const double mass_rl = node.declare_parameter<double>("vehicle.mass_rl");
  247. const double mass_rr = node.declare_parameter<double>("vehicle.mass_rr");
  248. const double cf = node.declare_parameter<double>("vehicle.cf");
  249. const double cr = node.declare_parameter<double>("vehicle.cr");
  250. // vehicle_model_ptr is only assigned in ctor, so parameter value have to be passed at init time
  251. vehicle_model_ptr =
  252. std::make_shared<DynamicsBicycleModel>(wheelbase, mass_fl, mass_fr, mass_rl, mass_rr, cf, cr);
  253. return vehicle_model_ptr;
  254. }
  255. RCLCPP_ERROR(logger_, "vehicle_model_type is undefined");
  256. return vehicle_model_ptr;
  257. }
  258. std::shared_ptr<QPSolverInterface> MpcLateralController::createQPSolverInterface(
  259. rclcpp::Node & node)
  260. {
  261. std::shared_ptr<QPSolverInterface> qpsolver_ptr;
  262. const std::string qp_solver_type = node.declare_parameter<std::string>("qp_solver_type");
  263. if (qp_solver_type == "unconstraint_fast") {
  264. qpsolver_ptr = std::make_shared<QPSolverEigenLeastSquareLLT>();
  265. return qpsolver_ptr;
  266. }
  267. if (qp_solver_type == "osqp") {
  268. qpsolver_ptr = std::make_shared<QPSolverOSQP>(logger_);
  269. return qpsolver_ptr;
  270. }
  271. RCLCPP_ERROR(logger_, "qp_solver_type is undefined");
  272. return qpsolver_ptr;
  273. }
  274. std::shared_ptr<SteeringOffsetEstimator> MpcLateralController::createSteerOffsetEstimator(
  275. const double wheelbase, rclcpp::Node & node)
  276. {
  277. const std::string ns = "steering_offset.";
  278. const auto vel_thres = node.declare_parameter<double>(ns + "update_vel_threshold");
  279. const auto steer_thres = node.declare_parameter<double>(ns + "update_steer_threshold");
  280. const auto limit = node.declare_parameter<double>(ns + "steering_offset_limit");
  281. const auto num = node.declare_parameter<int>(ns + "average_num");
  282. steering_offset_ =
  283. std::make_shared<SteeringOffsetEstimator>(wheelbase, num, vel_thres, steer_thres, limit);
  284. return steering_offset_;
  285. }
  286. trajectory_follower::LateralOutput MpcLateralController::run(
  287. trajectory_follower::InputData const & input_data)
  288. {
  289. // set input data
  290. setTrajectory(input_data.current_trajectory, input_data.current_odometry);
  291. m_current_kinematic_state = input_data.current_odometry;
  292. m_current_steering = input_data.current_steering;
  293. if (enable_auto_steering_offset_removal_) {
  294. m_current_steering.steering_tire_angle -= steering_offset_->getOffset();
  295. }
  296. AckermannLateralCommand ctrl_cmd;
  297. Trajectory predicted_traj;
  298. Float32MultiArrayStamped debug_values;
  299. if (!m_is_ctrl_cmd_prev_initialized) {
  300. m_ctrl_cmd_prev = getInitialControlCommand();
  301. m_is_ctrl_cmd_prev_initialized = true;
  302. }
  303. const bool is_mpc_solved = m_mpc.calculateMPC(
  304. m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values);
  305. // reset previous MPC result
  306. // Note: When a large deviation from the trajectory occurs, the optimization stops and
  307. // the vehicle will return to the path by re-planning the trajectory or external operation.
  308. // After the recovery, the previous value of the optimization may deviate greatly from
  309. // the actual steer angle, and it may make the optimization result unstable.
  310. if (!is_mpc_solved) {
  311. m_mpc.resetPrevResult(m_current_steering);
  312. } else {
  313. setSteeringToHistory(ctrl_cmd);
  314. }
  315. if (enable_auto_steering_offset_removal_) {
  316. steering_offset_->updateOffset(
  317. m_current_kinematic_state.twist.twist,
  318. input_data.current_steering.steering_tire_angle); // use unbiased steering
  319. ctrl_cmd.steering_tire_angle += steering_offset_->getOffset();
  320. }
  321. publishPredictedTraj(predicted_traj);
  322. publishDebugValues(debug_values);
  323. const auto createLateralOutput = [this](const auto & cmd, const bool is_mpc_solved) {
  324. trajectory_follower::LateralOutput output;
  325. output.control_cmd = createCtrlCmdMsg(cmd);
  326. // To be sure current steering of the vehicle is desired steering angle, we need to check
  327. // following conditions.
  328. // 1. At the last loop, mpc should be solved because command should be optimized output.
  329. // 2. The mpc should be converged.
  330. // 3. The steer angle should be converged.
  331. output.sync_data.is_steer_converged =
  332. is_mpc_solved && isMpcConverged() && isSteerConverged(cmd);
  333. return output;
  334. };
  335. if (isStoppedState()) {
  336. // Reset input buffer
  337. for (auto & value : m_mpc.m_input_buffer) {
  338. value = m_ctrl_cmd_prev.steering_tire_angle;
  339. }
  340. // Use previous command value as previous raw steer command
  341. m_mpc.m_raw_steer_cmd_prev = m_ctrl_cmd_prev.steering_tire_angle;
  342. return createLateralOutput(m_ctrl_cmd_prev, false);
  343. }
  344. if (!is_mpc_solved) {
  345. warn_throttle("MPC is not solved. publish 0 velocity.");
  346. ctrl_cmd = getStopControlCommand();
  347. }
  348. m_ctrl_cmd_prev = ctrl_cmd;
  349. return createLateralOutput(ctrl_cmd, is_mpc_solved);
  350. }
  351. bool MpcLateralController::isSteerConverged(const AckermannLateralCommand & cmd) const
  352. {
  353. // wait for a while to propagate the trajectory shape to the output command when the trajectory
  354. // shape is changed.
  355. if (!m_has_received_first_trajectory || isTrajectoryShapeChanged()) {
  356. RCLCPP_DEBUG(logger_, "trajectory shaped is changed");
  357. return false;
  358. }
  359. const bool is_converged =
  360. std::abs(cmd.steering_tire_angle - m_current_steering.steering_tire_angle) <
  361. static_cast<float>(m_converged_steer_rad);
  362. return is_converged;
  363. }
  364. bool MpcLateralController::isReady(const trajectory_follower::InputData & input_data)
  365. {
  366. setTrajectory(input_data.current_trajectory, input_data.current_odometry);
  367. m_current_kinematic_state = input_data.current_odometry;
  368. m_current_steering = input_data.current_steering;
  369. if (!m_mpc.hasVehicleModel()) {
  370. info_throttle("MPC does not have a vehicle model");
  371. return false;
  372. }
  373. if (!m_mpc.hasQPSolver()) {
  374. info_throttle("MPC does not have a QP solver");
  375. return false;
  376. }
  377. if (m_mpc.m_reference_trajectory.empty()) {
  378. info_throttle("trajectory size is zero.");
  379. return false;
  380. }
  381. return true;
  382. }
  383. void MpcLateralController::setTrajectory(
  384. const Trajectory & msg, const Odometry & current_kinematics)
  385. {
  386. m_current_trajectory = msg;
  387. if (msg.points.size() < 3) {
  388. RCLCPP_DEBUG(logger_, "received path size is < 3, not enough.");
  389. return;
  390. }
  391. if (!isValidTrajectory(msg)) {
  392. RCLCPP_ERROR(logger_, "Trajectory is invalid!! stop computing.");
  393. return;
  394. }
  395. m_mpc.setReferenceTrajectory(msg, m_trajectory_filtering_param, current_kinematics);
  396. // update trajectory buffer to check the trajectory shape change.
  397. m_trajectory_buffer.push_back(m_current_trajectory);
  398. while (rclcpp::ok()) {
  399. const auto time_diff = rclcpp::Time(m_trajectory_buffer.back().header.stamp) -
  400. rclcpp::Time(m_trajectory_buffer.front().header.stamp);
  401. const double first_trajectory_duration_time = 5.0;
  402. const double duration_time =
  403. m_has_received_first_trajectory ? m_new_traj_duration_time : first_trajectory_duration_time;
  404. if (time_diff.seconds() < duration_time) {
  405. m_has_received_first_trajectory = true;
  406. break;
  407. }
  408. m_trajectory_buffer.pop_front();
  409. }
  410. }
  411. AckermannLateralCommand MpcLateralController::getStopControlCommand() const
  412. {
  413. AckermannLateralCommand cmd;
  414. cmd.steering_tire_angle = static_cast<decltype(cmd.steering_tire_angle)>(m_steer_cmd_prev);
  415. cmd.steering_tire_rotation_rate = 0.0;
  416. return cmd;
  417. }
  418. AckermannLateralCommand MpcLateralController::getInitialControlCommand() const
  419. {
  420. AckermannLateralCommand cmd;
  421. cmd.steering_tire_angle = m_current_steering.steering_tire_angle;
  422. cmd.steering_tire_rotation_rate = 0.0;
  423. return cmd;
  424. }
  425. bool MpcLateralController::isStoppedState() const
  426. {
  427. // If the nearest index is not found, return false
  428. if (m_current_trajectory.points.empty()) {
  429. return false;
  430. }
  431. // Note: This function used to take into account the distance to the stop line
  432. // for the stop state judgement. However, it has been removed since the steering
  433. // control was turned off when approaching/exceeding the stop line on a curve or
  434. // emergency stop situation and it caused large tracking error.
  435. const size_t nearest = motion_utils::findFirstNearestIndexWithSoftConstraints(
  436. m_current_trajectory.points, m_current_kinematic_state.pose.pose, m_ego_nearest_dist_threshold,
  437. m_ego_nearest_yaw_threshold);
  438. const double current_vel = m_current_kinematic_state.twist.twist.linear.x;
  439. const double target_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps;
  440. const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
  441. if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) {
  442. return false; // not stopState: keep control
  443. }
  444. if (
  445. std::fabs(current_vel) < m_stop_state_entry_ego_speed &&
  446. std::fabs(target_vel) < m_stop_state_entry_target_speed) {
  447. return true;
  448. } else {
  449. return false;
  450. }
  451. }
  452. AckermannLateralCommand MpcLateralController::createCtrlCmdMsg(
  453. const AckermannLateralCommand & ctrl_cmd)
  454. {
  455. auto out = ctrl_cmd;
  456. out.stamp = clock_->now();
  457. m_steer_cmd_prev = out.steering_tire_angle;
  458. return out;
  459. }
  460. void MpcLateralController::publishPredictedTraj(Trajectory & predicted_traj) const
  461. {
  462. predicted_traj.header.stamp = clock_->now();
  463. predicted_traj.header.frame_id = m_current_trajectory.header.frame_id;
  464. m_pub_predicted_traj->publish(predicted_traj);
  465. }
  466. void MpcLateralController::publishDebugValues(Float32MultiArrayStamped & debug_values) const
  467. {
  468. debug_values.stamp = clock_->now();
  469. m_pub_debug_values->publish(debug_values);
  470. Float32Stamped offset;
  471. offset.stamp = clock_->now();
  472. offset.data = steering_offset_->getOffset();
  473. m_pub_steer_offset->publish(offset);
  474. }
  475. void MpcLateralController::setSteeringToHistory(const AckermannLateralCommand & steering)
  476. {
  477. const auto time = clock_->now();
  478. if (m_mpc_steering_history.empty()) {
  479. m_mpc_steering_history.emplace_back(steering, time);
  480. m_is_mpc_history_filled = false;
  481. return;
  482. }
  483. m_mpc_steering_history.emplace_back(steering, time);
  484. // Check the history is filled or not.
  485. if (rclcpp::Duration(time - m_mpc_steering_history.begin()->second).seconds() >= 1.0) {
  486. m_is_mpc_history_filled = true;
  487. // remove old data that is older than 1 sec
  488. for (auto itr = m_mpc_steering_history.begin(); itr != m_mpc_steering_history.end(); ++itr) {
  489. if (rclcpp::Duration(time - itr->second).seconds() > 1.0) {
  490. m_mpc_steering_history.erase(m_mpc_steering_history.begin());
  491. } else {
  492. break;
  493. }
  494. }
  495. } else {
  496. m_is_mpc_history_filled = false;
  497. }
  498. }
  499. bool MpcLateralController::isMpcConverged()
  500. {
  501. // If the number of variable below the 2, there is no enough data so MPC is not converged.
  502. if (m_mpc_steering_history.size() < 2) {
  503. return false;
  504. }
  505. // If the history is not filled, return false.
  506. if (!m_is_mpc_history_filled) {
  507. return false;
  508. }
  509. // Find the maximum and minimum values of the steering angle in the past 1 second.
  510. double min_steering_value = m_mpc_steering_history[0].first.steering_tire_angle;
  511. double max_steering_value = m_mpc_steering_history[0].first.steering_tire_angle;
  512. for (size_t i = 1; i < m_mpc_steering_history.size(); i++) {
  513. if (m_mpc_steering_history.at(i).first.steering_tire_angle < min_steering_value) {
  514. min_steering_value = m_mpc_steering_history.at(i).first.steering_tire_angle;
  515. }
  516. if (m_mpc_steering_history.at(i).first.steering_tire_angle > max_steering_value) {
  517. max_steering_value = m_mpc_steering_history.at(i).first.steering_tire_angle;
  518. }
  519. }
  520. return (max_steering_value - min_steering_value) < m_mpc_converged_threshold_rps;
  521. }
  522. void MpcLateralController::declareMPCparameters(rclcpp::Node & node)
  523. {
  524. m_mpc.m_param.prediction_horizon = node.declare_parameter<int>("mpc_prediction_horizon");
  525. m_mpc.m_param.prediction_dt = node.declare_parameter<double>("mpc_prediction_dt");
  526. const auto dp = [&](const auto & param) { return node.declare_parameter<double>(param); };
  527. auto & nw = m_mpc.m_param.nominal_weight;
  528. nw.lat_error = dp("mpc_weight_lat_error");
  529. nw.heading_error = dp("mpc_weight_heading_error");
  530. nw.heading_error_squared_vel = dp("mpc_weight_heading_error_squared_vel");
  531. nw.steering_input = dp("mpc_weight_steering_input");
  532. nw.steering_input_squared_vel = dp("mpc_weight_steering_input_squared_vel");
  533. nw.lat_jerk = dp("mpc_weight_lat_jerk");
  534. nw.steer_rate = dp("mpc_weight_steer_rate");
  535. nw.steer_acc = dp("mpc_weight_steer_acc");
  536. nw.terminal_lat_error = dp("mpc_weight_terminal_lat_error");
  537. nw.terminal_heading_error = dp("mpc_weight_terminal_heading_error");
  538. auto & lcw = m_mpc.m_param.low_curvature_weight;
  539. lcw.lat_error = dp("mpc_low_curvature_weight_lat_error");
  540. lcw.heading_error = dp("mpc_low_curvature_weight_heading_error");
  541. lcw.heading_error_squared_vel = dp("mpc_low_curvature_weight_heading_error_squared_vel");
  542. lcw.steering_input = dp("mpc_low_curvature_weight_steering_input");
  543. lcw.steering_input_squared_vel = dp("mpc_low_curvature_weight_steering_input_squared_vel");
  544. lcw.lat_jerk = dp("mpc_low_curvature_weight_lat_jerk");
  545. lcw.steer_rate = dp("mpc_low_curvature_weight_steer_rate");
  546. lcw.steer_acc = dp("mpc_low_curvature_weight_steer_acc");
  547. m_mpc.m_param.low_curvature_thresh_curvature = dp("mpc_low_curvature_thresh_curvature");
  548. m_mpc.m_param.zero_ff_steer_deg = dp("mpc_zero_ff_steer_deg");
  549. m_mpc.m_param.acceleration_limit = dp("mpc_acceleration_limit");
  550. m_mpc.m_param.velocity_time_constant = dp("mpc_velocity_time_constant");
  551. m_mpc.m_param.min_prediction_length = dp("mpc_min_prediction_length");
  552. }
  553. rcl_interfaces::msg::SetParametersResult MpcLateralController::paramCallback(
  554. const std::vector<rclcpp::Parameter> & parameters)
  555. {
  556. rcl_interfaces::msg::SetParametersResult result;
  557. result.successful = true;
  558. result.reason = "success";
  559. // strong exception safety wrt MPCParam
  560. MPCParam param = m_mpc.m_param;
  561. auto & nw = param.nominal_weight;
  562. auto & lcw = param.low_curvature_weight;
  563. using MPCUtils::update_param;
  564. try {
  565. update_param(parameters, "mpc_prediction_horizon", param.prediction_horizon);
  566. update_param(parameters, "mpc_prediction_dt", param.prediction_dt);
  567. const std::string ns_nw = "mpc_weight_";
  568. update_param(parameters, ns_nw + "lat_error", nw.lat_error);
  569. update_param(parameters, ns_nw + "heading_error", nw.heading_error);
  570. update_param(parameters, ns_nw + "heading_error_squared_vel", nw.heading_error_squared_vel);
  571. update_param(parameters, ns_nw + "steering_input", nw.steering_input);
  572. update_param(parameters, ns_nw + "steering_input_squared_vel", nw.steering_input_squared_vel);
  573. update_param(parameters, ns_nw + "lat_jerk", nw.lat_jerk);
  574. update_param(parameters, ns_nw + "steer_rate", nw.steer_rate);
  575. update_param(parameters, ns_nw + "steer_acc", nw.steer_acc);
  576. update_param(parameters, ns_nw + "terminal_lat_error", nw.terminal_lat_error);
  577. update_param(parameters, ns_nw + "terminal_heading_error", nw.terminal_heading_error);
  578. const std::string ns_lcw = "mpc_low_curvature_weight_";
  579. update_param(parameters, ns_lcw + "lat_error", lcw.lat_error);
  580. update_param(parameters, ns_lcw + "heading_error", lcw.heading_error);
  581. update_param(parameters, ns_lcw + "heading_error_squared_vel", lcw.heading_error_squared_vel);
  582. update_param(parameters, ns_lcw + "steering_input", lcw.steering_input);
  583. update_param(parameters, ns_lcw + "steering_input_squared_vel", lcw.steering_input_squared_vel);
  584. update_param(parameters, ns_lcw + "lat_jerk", lcw.lat_jerk);
  585. update_param(parameters, ns_lcw + "steer_rate", lcw.steer_rate);
  586. update_param(parameters, ns_lcw + "steer_acc", lcw.steer_acc);
  587. update_param(
  588. parameters, "mpc_low_curvature_thresh_curvature", param.low_curvature_thresh_curvature);
  589. update_param(parameters, "mpc_zero_ff_steer_deg", param.zero_ff_steer_deg);
  590. update_param(parameters, "mpc_acceleration_limit", param.acceleration_limit);
  591. update_param(parameters, "mpc_velocity_time_constant", param.velocity_time_constant);
  592. update_param(parameters, "mpc_min_prediction_length", param.min_prediction_length);
  593. // initialize input buffer
  594. update_param(parameters, "input_delay", param.input_delay);
  595. const double delay_step = std::round(param.input_delay / m_mpc.m_ctrl_period);
  596. const double delay = delay_step * m_mpc.m_ctrl_period;
  597. if (param.input_delay != delay) {
  598. param.input_delay = delay;
  599. m_mpc.m_input_buffer = std::deque<double>(static_cast<size_t>(delay_step), 0.0);
  600. }
  601. // transaction succeeds, now assign values
  602. m_mpc.m_param = param;
  603. } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
  604. result.successful = false;
  605. result.reason = e.what();
  606. }
  607. return result;
  608. }
  609. bool MpcLateralController::isTrajectoryShapeChanged() const
  610. {
  611. // TODO(Horibe): update implementation to check trajectory shape around ego vehicle.
  612. // Now temporally check the goal position.
  613. for (const auto & trajectory : m_trajectory_buffer) {
  614. const auto change_distance = tier4_autoware_utils::calcDistance2d(
  615. trajectory.points.back().pose, m_current_trajectory.points.back().pose);
  616. if (change_distance > m_new_traj_end_dist) {
  617. return true;
  618. }
  619. }
  620. return false;
  621. }
  622. bool MpcLateralController::isValidTrajectory(const Trajectory & traj) const
  623. {
  624. for (const auto & p : traj.points) {
  625. if (
  626. !isfinite(p.pose.position.x) || !isfinite(p.pose.position.y) ||
  627. !isfinite(p.pose.orientation.w) || !isfinite(p.pose.orientation.x) ||
  628. !isfinite(p.pose.orientation.y) || !isfinite(p.pose.orientation.z) ||
  629. !isfinite(p.longitudinal_velocity_mps) || !isfinite(p.lateral_velocity_mps) ||
  630. !isfinite(p.lateral_velocity_mps) || !isfinite(p.heading_rate_rps) ||
  631. !isfinite(p.front_wheel_angle_rad) || !isfinite(p.rear_wheel_angle_rad)) {
  632. return false;
  633. }
  634. }
  635. return true;
  636. }
  637. } // namespace autoware::motion::control::mpc_lateral_controller