mpc_utils.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462
  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_utils.hpp"
  15. #include "interpolation/linear_interpolation.hpp"
  16. #include "interpolation/spline_interpolation.hpp"
  17. #include "motion_utils/trajectory/trajectory.hpp"
  18. #include "tier4_autoware_utils/geometry/geometry.hpp"
  19. #include "tier4_autoware_utils/math/normalization.hpp"
  20. #include <algorithm>
  21. #include <limits>
  22. #include <string>
  23. #include <vector>
  24. namespace autoware::motion::control::mpc_lateral_controller
  25. {
  26. namespace
  27. {
  28. double calcLongitudinalOffset(
  29. const geometry_msgs::msg::Point & p_front, const geometry_msgs::msg::Point & p_back,
  30. const geometry_msgs::msg::Point & p_target)
  31. {
  32. const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0};
  33. const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0};
  34. return segment_vec.dot(target_vec) / segment_vec.norm();
  35. }
  36. } // namespace
  37. namespace MPCUtils
  38. {
  39. //using tier4_autoware_utils::calcDistance2d;
  40. //using tier4_autoware_utils::createQuaternionFromYaw;
  41. //using tier4_autoware_utils::normalizeRadian;
  42. double calcDistance2d(const MPCTrajectory & trajectory, const size_t idx1, const size_t idx2)
  43. {
  44. const double dx = trajectory.x.at(idx1) - trajectory.x.at(idx2);
  45. const double dy = trajectory.y.at(idx1) - trajectory.y.at(idx2);
  46. return std::hypot(dx, dy);
  47. }
  48. double calcDistance3d(const MPCTrajectory & trajectory, const size_t idx1, const size_t idx2)
  49. {
  50. const double dx = trajectory.x.at(idx1) - trajectory.x.at(idx2);
  51. const double dy = trajectory.y.at(idx1) - trajectory.y.at(idx2);
  52. const double dz = trajectory.z.at(idx1) - trajectory.z.at(idx2);
  53. return std::hypot(dx, dy, dz);
  54. }
  55. void convertEulerAngleToMonotonic(std::vector<double> & angle_vector)
  56. {
  57. for (uint i = 1; i < angle_vector.size(); ++i) {
  58. const double da = angle_vector.at(i) - angle_vector.at(i - 1);
  59. angle_vector.at(i) = angle_vector.at(i - 1) + normalizeRadian(da);
  60. }
  61. }
  62. double calcLateralError(const Pose & ego_pose, const Pose & ref_pose)
  63. {
  64. const double err_x = ego_pose.position.x - ref_pose.position.x;
  65. const double err_y = ego_pose.position.y - ref_pose.position.y;
  66. const double ref_yaw = tf2::getYaw(ref_pose.orientation);
  67. const double lat_err = -std::sin(ref_yaw) * err_x + std::cos(ref_yaw) * err_y;
  68. return lat_err;
  69. }
  70. void calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory, std::vector<double> & arc_length)
  71. {
  72. double dist = 0.0;
  73. arc_length.clear();
  74. arc_length.push_back(dist);
  75. for (uint i = 1; i < trajectory.size(); ++i) {
  76. dist += calcDistance2d(trajectory, i, i - 1);
  77. arc_length.push_back(dist);
  78. }
  79. }
  80. std::pair<bool, MPCTrajectory> resampleMPCTrajectoryByDistance(
  81. const MPCTrajectory & input, const double resample_interval_dist, const size_t nearest_seg_idx,
  82. const double ego_offset_to_segment)
  83. {
  84. MPCTrajectory output;
  85. if (input.empty()) {
  86. return {true, output};
  87. }
  88. std::vector<double> input_arclength;
  89. calcMPCTrajectoryArcLength(input, input_arclength);
  90. if (input_arclength.empty()) {
  91. return {false, output};
  92. }
  93. std::vector<double> output_arclength;
  94. // To accurately sample the ego point, resample separately in the forward direction and the
  95. // backward direction from the current position.
  96. for (double s = std::clamp(
  97. input_arclength.at(nearest_seg_idx) + ego_offset_to_segment, 0.0,
  98. input_arclength.back() - 1e-6);
  99. 0 <= s; s -= resample_interval_dist) {
  100. output_arclength.push_back(s);
  101. }
  102. std::reverse(output_arclength.begin(), output_arclength.end());
  103. for (double s = std::max(input_arclength.at(nearest_seg_idx) + ego_offset_to_segment, 0.0) +
  104. resample_interval_dist;
  105. s < input_arclength.back(); s += resample_interval_dist) {
  106. output_arclength.push_back(s);
  107. }
  108. std::vector<double> input_yaw = input.yaw;
  109. convertEulerAngleToMonotonic(input_yaw);
  110. const auto lerp_arc_length = [&](const auto & input_value) {
  111. return interpolation::lerp(input_arclength, input_value, output_arclength);
  112. };
  113. const auto spline_arc_length = [&](const auto & input_value) {
  114. return interpolation::spline(input_arclength, input_value, output_arclength);
  115. };
  116. output.x = spline_arc_length(input.x);
  117. output.y = spline_arc_length(input.y);
  118. output.z = spline_arc_length(input.z);
  119. output.yaw = spline_arc_length(input.yaw);
  120. output.vx = lerp_arc_length(input.vx); // must be linear
  121. output.k = spline_arc_length(input.k);
  122. output.smooth_k = spline_arc_length(input.smooth_k);
  123. output.relative_time = lerp_arc_length(input.relative_time); // must be linear
  124. return {true, output};
  125. }
  126. bool linearInterpMPCTrajectory(
  127. const std::vector<double> & in_index, const MPCTrajectory & in_traj,
  128. const std::vector<double> & out_index, MPCTrajectory & out_traj)
  129. {
  130. if (in_traj.empty()) {
  131. out_traj = in_traj;
  132. return true;
  133. }
  134. std::vector<double> in_traj_yaw = in_traj.yaw;
  135. convertEulerAngleToMonotonic(in_traj_yaw);
  136. const auto lerp_arc_length = [&](const auto & input_value) {
  137. return interpolation::lerp(in_index, input_value, out_index);
  138. };
  139. try {
  140. out_traj.x = lerp_arc_length(in_traj.x);
  141. out_traj.y = lerp_arc_length(in_traj.y);
  142. out_traj.z = lerp_arc_length(in_traj.z);
  143. out_traj.yaw = lerp_arc_length(in_traj.yaw);
  144. out_traj.vx = lerp_arc_length(in_traj.vx);
  145. out_traj.k = lerp_arc_length(in_traj.k);
  146. out_traj.smooth_k = lerp_arc_length(in_traj.smooth_k);
  147. out_traj.relative_time = lerp_arc_length(in_traj.relative_time);
  148. } catch (const std::exception & e) {
  149. std::cerr << "linearInterpMPCTrajectory error!: " << e.what() << std::endl;
  150. }
  151. if (out_traj.empty()) {
  152. std::cerr << "[mpc util] linear interpolation error" << std::endl;
  153. return false;
  154. }
  155. return true;
  156. }
  157. void calcTrajectoryYawFromXY(MPCTrajectory & traj, const bool is_forward_shift)
  158. {
  159. if (traj.yaw.size() < 3) { // at least 3 points are required to calculate yaw
  160. return;
  161. }
  162. if (traj.yaw.size() != traj.vx.size()) {
  163. RCLCPP_ERROR(rclcpp::get_logger("mpc_utils"), "trajectory size has no consistency.");
  164. return;
  165. }
  166. // interpolate yaw
  167. for (int i = 1; i < static_cast<int>(traj.yaw.size()) - 1; ++i) {
  168. const double dx = traj.x.at(i + 1) - traj.x.at(i - 1);
  169. const double dy = traj.y.at(i + 1) - traj.y.at(i - 1);
  170. traj.yaw.at(i) = is_forward_shift ? std::atan2(dy, dx) : std::atan2(dy, dx) + M_PI;
  171. }
  172. if (traj.yaw.size() > 1) {
  173. traj.yaw.at(0) = traj.yaw.at(1);
  174. traj.yaw.back() = traj.yaw.at(traj.yaw.size() - 2);
  175. }
  176. }
  177. void calcTrajectoryCurvature(
  178. const int curvature_smoothing_num_traj, const int curvature_smoothing_num_ref_steer,
  179. MPCTrajectory & traj)
  180. {
  181. traj.k = calcTrajectoryCurvature(curvature_smoothing_num_traj, traj);
  182. traj.smooth_k = calcTrajectoryCurvature(curvature_smoothing_num_ref_steer, traj);
  183. }
  184. std::vector<double> calcTrajectoryCurvature(
  185. const int curvature_smoothing_num, const MPCTrajectory & traj)
  186. {
  187. std::vector<double> curvature_vec(traj.x.size());
  188. /* calculate curvature by circle fitting from three points */
  189. geometry_msgs::msg::Point p1, p2, p3;
  190. const int max_smoothing_num =
  191. static_cast<int>(std::floor(0.5 * (static_cast<double>(traj.x.size() - 1))));
  192. const size_t L = static_cast<size_t>(std::min(curvature_smoothing_num, max_smoothing_num));
  193. for (size_t i = L; i < traj.x.size() - L; ++i) {
  194. const size_t curr_idx = i;
  195. const size_t prev_idx = curr_idx - L;
  196. const size_t next_idx = curr_idx + L;
  197. p1.x = traj.x.at(prev_idx);
  198. p2.x = traj.x.at(curr_idx);
  199. p3.x = traj.x.at(next_idx);
  200. p1.y = traj.y.at(prev_idx);
  201. p2.y = traj.y.at(curr_idx);
  202. p3.y = traj.y.at(next_idx);
  203. try {
  204. curvature_vec.at(curr_idx) = tier4_autoware_utils::calcCurvature(p1, p2, p3);
  205. } catch (...) {
  206. std::cerr << "[MPC] 2 points are too close to calculate curvature." << std::endl;
  207. curvature_vec.at(curr_idx) = 0.0;
  208. }
  209. }
  210. /* first and last curvature is copied from next value */
  211. for (size_t i = 0; i < std::min(L, traj.x.size()); ++i) {
  212. curvature_vec.at(i) = curvature_vec.at(std::min(L, traj.x.size() - 1));
  213. curvature_vec.at(traj.x.size() - i - 1) =
  214. curvature_vec.at(std::max(traj.x.size() - L - 1, size_t(0)));
  215. }
  216. return curvature_vec;
  217. }
  218. MPCTrajectory convertToMPCTrajectory(const Trajectory & input)
  219. {
  220. MPCTrajectory output;
  221. for (const TrajectoryPoint & p : input.points) {
  222. const double x = p.pose.position.x;
  223. const double y = p.pose.position.y;
  224. const double z = p.pose.position.z;
  225. const double yaw = tf2::getYaw(p.pose.orientation);
  226. const double vx = p.longitudinal_velocity_mps;
  227. const double k = 0.0;
  228. const double t = 0.0;
  229. output.push_back(x, y, z, yaw, vx, k, k, t);
  230. }
  231. calcMPCTrajectoryTime(output);
  232. return output;
  233. }
  234. Trajectory convertToAutowareTrajectory(const MPCTrajectory & input)
  235. {
  236. Trajectory output;
  237. TrajectoryPoint p;
  238. for (size_t i = 0; i < input.size(); ++i) {
  239. p.pose.position.x = input.x.at(i);
  240. p.pose.position.y = input.y.at(i);
  241. p.pose.position.z = input.z.at(i);
  242. p.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(input.yaw.at(i));
  243. p.longitudinal_velocity_mps =
  244. static_cast<decltype(p.longitudinal_velocity_mps)>(input.vx.at(i));
  245. output.points.push_back(p);
  246. if (output.points.size() == output.points.max_size()) {
  247. break;
  248. }
  249. }
  250. return output;
  251. }
  252. bool calcMPCTrajectoryTime(MPCTrajectory & traj)
  253. {
  254. constexpr auto min_dt = 1.0e-4; // must be positive value to avoid duplication in time
  255. double t = 0.0;
  256. traj.relative_time.clear();
  257. traj.relative_time.push_back(t);
  258. for (size_t i = 0; i < traj.x.size() - 1; ++i) {
  259. const double dist = calcDistance3d(traj, i, i + 1);
  260. const double v = std::max(std::fabs(traj.vx.at(i)), 0.1);
  261. t += std::max(dist / v, min_dt);
  262. traj.relative_time.push_back(t);
  263. }
  264. return true;
  265. }
  266. void dynamicSmoothingVelocity(
  267. const size_t start_seg_idx, const double start_vel, const double acc_lim, const double tau,
  268. MPCTrajectory & traj)
  269. {
  270. double curr_v = start_vel;
  271. // set current velocity in both start and end point of the segment
  272. traj.vx.at(start_seg_idx) = start_vel;
  273. if (1 < traj.vx.size()) {
  274. traj.vx.at(start_seg_idx + 1) = start_vel;
  275. }
  276. for (size_t i = start_seg_idx + 2; i < traj.size(); ++i) {
  277. const double ds = calcDistance2d(traj, i, i - 1);
  278. const double dt = ds / std::max(std::fabs(curr_v), std::numeric_limits<double>::epsilon());
  279. const double a = tau / std::max(tau + dt, std::numeric_limits<double>::epsilon());
  280. const double updated_v = a * curr_v + (1.0 - a) * traj.vx.at(i);
  281. const double dv = std::max(-acc_lim * dt, std::min(acc_lim * dt, updated_v - curr_v));
  282. curr_v = curr_v + dv;
  283. traj.vx.at(i) = curr_v;
  284. }
  285. calcMPCTrajectoryTime(traj);
  286. }
  287. bool calcNearestPoseInterp(
  288. const MPCTrajectory & traj, const Pose & self_pose, Pose * nearest_pose, size_t * nearest_index,
  289. double * nearest_time, const double max_dist, const double max_yaw)
  290. {
  291. if (traj.empty() || !nearest_pose || !nearest_index || !nearest_time) {
  292. return false;
  293. }
  294. const auto autoware_traj = convertToAutowareTrajectory(traj);
  295. if (autoware_traj.points.empty()) {
  296. const auto logger = rclcpp::get_logger("mpc_util");
  297. auto clock = rclcpp::Clock(RCL_ROS_TIME);
  298. RCLCPP_WARN_THROTTLE(logger, clock, 5000, "[calcNearestPoseInterp] input trajectory is empty");
  299. return false;
  300. }
  301. *nearest_index = motion_utils::findFirstNearestIndexWithSoftConstraints(
  302. autoware_traj.points, self_pose, max_dist, max_yaw);
  303. const size_t traj_size = traj.size();
  304. if (traj.size() == 1) {
  305. nearest_pose->position.x = traj.x.at(*nearest_index);
  306. nearest_pose->position.y = traj.y.at(*nearest_index);
  307. nearest_pose->orientation = createQuaternionFromYaw(traj.yaw.at(*nearest_index));
  308. *nearest_time = traj.relative_time.at(*nearest_index);
  309. return true;
  310. }
  311. /* get second nearest index = next to nearest_index */
  312. const auto [prev, next] = [&]() -> std::pair<size_t, size_t> {
  313. if (*nearest_index == 0) {
  314. return std::make_pair(0, 1);
  315. }
  316. if (*nearest_index == traj_size - 1) {
  317. return std::make_pair(traj_size - 2, traj_size - 1);
  318. }
  319. geometry_msgs::msg::Point nearest_traj_point;
  320. nearest_traj_point.x = traj.x.at(*nearest_index);
  321. nearest_traj_point.y = traj.y.at(*nearest_index);
  322. geometry_msgs::msg::Point next_nearest_traj_point;
  323. next_nearest_traj_point.x = traj.x.at(*nearest_index + 1);
  324. next_nearest_traj_point.y = traj.y.at(*nearest_index + 1);
  325. const double signed_length =
  326. calcLongitudinalOffset(nearest_traj_point, next_nearest_traj_point, self_pose.position);
  327. if (signed_length <= 0) {
  328. return std::make_pair(*nearest_index - 1, *nearest_index);
  329. }
  330. return std::make_pair(*nearest_index, *nearest_index + 1);
  331. }();
  332. geometry_msgs::msg::Point next_traj_point;
  333. next_traj_point.x = traj.x.at(next);
  334. next_traj_point.y = traj.y.at(next);
  335. geometry_msgs::msg::Point prev_traj_point;
  336. prev_traj_point.x = traj.x.at(prev);
  337. prev_traj_point.y = traj.y.at(prev);
  338. const double traj_seg_length =
  339. tier4_autoware_utils::calcDistance2d(prev_traj_point, next_traj_point);
  340. /* if distance between two points are too close */
  341. if (traj_seg_length < 1.0E-5) {
  342. nearest_pose->position.x = traj.x.at(*nearest_index);
  343. nearest_pose->position.y = traj.y.at(*nearest_index);
  344. nearest_pose->orientation = createQuaternionFromYaw(traj.yaw.at(*nearest_index));
  345. *nearest_time = traj.relative_time.at(*nearest_index);
  346. return true;
  347. }
  348. /* linear interpolation */
  349. const double ratio = std::clamp(
  350. calcLongitudinalOffset(prev_traj_point, next_traj_point, self_pose.position) / traj_seg_length,
  351. 0.0, 1.0);
  352. nearest_pose->position.x = (1 - ratio) * traj.x.at(prev) + ratio * traj.x.at(next);
  353. nearest_pose->position.y = (1 - ratio) * traj.y.at(prev) + ratio * traj.y.at(next);
  354. const double tmp_yaw_err = normalizeRadian(traj.yaw.at(prev) - traj.yaw.at(next));
  355. const double nearest_yaw = normalizeRadian(traj.yaw.at(next) + (1 - ratio) * tmp_yaw_err);
  356. nearest_pose->orientation = createQuaternionFromYaw(nearest_yaw);
  357. *nearest_time = (1 - ratio) * traj.relative_time.at(prev) + ratio * traj.relative_time.at(next);
  358. return true;
  359. }
  360. double calcStopDistance(const Trajectory & current_trajectory, const int origin)
  361. {
  362. constexpr float zero_velocity = std::numeric_limits<float>::epsilon();
  363. const float origin_velocity =
  364. current_trajectory.points.at(static_cast<size_t>(origin)).longitudinal_velocity_mps;
  365. double stop_dist = 0.0;
  366. // search forward
  367. if (std::fabs(origin_velocity) > zero_velocity) {
  368. for (int i = origin + 1; i < static_cast<int>(current_trajectory.points.size()) - 1; ++i) {
  369. const auto & p0 = current_trajectory.points.at(i);
  370. const auto & p1 = current_trajectory.points.at(i - 1);
  371. stop_dist += calcDistance2d(p0, p1);
  372. if (std::fabs(p0.longitudinal_velocity_mps) < zero_velocity) {
  373. break;
  374. }
  375. }
  376. return stop_dist;
  377. }
  378. // search backward
  379. for (int i = origin - 1; 0 < i; --i) {
  380. const auto & p0 = current_trajectory.points.at(i);
  381. const auto & p1 = current_trajectory.points.at(i + 1);
  382. if (std::fabs(p0.longitudinal_velocity_mps) > zero_velocity) {
  383. break;
  384. }
  385. stop_dist -= calcDistance2d(p0, p1);
  386. }
  387. return stop_dist;
  388. }
  389. void extendTrajectoryInYawDirection(
  390. const double yaw, const double interval, const bool is_forward_shift, MPCTrajectory & traj)
  391. {
  392. // set terminal yaw
  393. traj.yaw.back() = yaw;
  394. // get terminal pose
  395. const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(traj);
  396. auto extended_pose = autoware_traj.points.back().pose;
  397. constexpr double extend_dist = 10.0;
  398. constexpr double extend_vel = 10.0;
  399. const double x_offset = is_forward_shift ? interval : -interval;
  400. const double dt = interval / extend_vel;
  401. const size_t num_extended_point = static_cast<size_t>(extend_dist / interval);
  402. for (size_t i = 0; i < num_extended_point; ++i) {
  403. extended_pose = tier4_autoware_utils::calcOffsetPose(extended_pose, x_offset, 0.0, 0.0);
  404. traj.push_back(
  405. extended_pose.position.x, extended_pose.position.y, extended_pose.position.z, traj.yaw.back(),
  406. extend_vel, traj.k.back(), traj.smooth_k.back(), traj.relative_time.back() + dt);
  407. }
  408. }
  409. } // namespace MPCUtils
  410. } // namespace autoware::motion::control::mpc_lateral_controller