mpc_utils.hpp 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255
  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. #ifndef MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
  15. #define MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_
  16. //#include "rclcpp/rclcpp.hpp"
  17. //#include "tf2/utils.h"
  18. #include <Eigen/Core>
  19. //#ifdef ROS_DISTRO_GALACTIC
  20. //#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
  21. //#else
  22. //#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
  23. //#endif
  24. #include "mpc_lateral_controller/mpc_trajectory.hpp"
  25. //#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
  26. //#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp"
  27. //#include "geometry_msgs/msg/pose_stamped.hpp"
  28. //#include "geometry_msgs/msg/twist_stamped.hpp"
  29. #include <cmath>
  30. #include <string>
  31. #include <utility>
  32. #include <vector>
  33. #include "ivtype/ivpose.h"
  34. namespace autoware::motion::control::mpc_lateral_controller
  35. {
  36. namespace MPCUtils
  37. {
  38. //using autoware_auto_planning_msgs::msg::Trajectory;
  39. //using autoware_auto_planning_msgs::msg::TrajectoryPoint;
  40. //using geometry_msgs::msg::Pose;
  41. double ADCgetYaw(iv::ADCQuaternion q);
  42. double ADCnormalizeRadian(const double rad, const double min_rad = -M_PI);
  43. double ADCcalcYawDeviation(
  44. const double & base_yaw, const iv::ADCPose & target_pose);
  45. double ADCcalcDistance2d(iv::ADCPoint p1, iv::ADCPoint p2);
  46. double calcLongitudinalOffsetToSegment(
  47. const MPCTrajectory & currenttraj, const size_t seg_idx, const iv::ADCPoint & p_target,
  48. const bool throw_exception = false);
  49. size_t findFirstNearestSegmentIndexWithSoftConstraints(
  50. const MPCTrajectory & currenttraj, const iv::ADCPose & pose,
  51. const double dist_threshold = std::numeric_limits<double>::max(),
  52. const double yaw_threshold = std::numeric_limits<double>::max());
  53. size_t findFirstNearestIndexWithSoftConstraints(
  54. const MPCTrajectory & currenttraj, const iv::ADCPose & pose,
  55. const double dist_threshold = std::numeric_limits<double>::max(),
  56. const double yaw_threshold = std::numeric_limits<double>::max());
  57. bool isDrivingForward(const MPCTrajectory & currenttraj);
  58. constexpr double deg2rad(const double deg);
  59. /**
  60. * @brief calculate 2d distance from trajectory[idx1] to trajectory[idx2]
  61. */
  62. double calcDistance2d(const MPCTrajectory & trajectory, const size_t idx1, const size_t idx2);
  63. /**
  64. * @brief calculate 3d distance from trajectory[idx1] to trajectory[idx2]
  65. */
  66. double calcDistance3d(const MPCTrajectory & trajectory, const size_t idx1, const size_t idx2);
  67. /**
  68. * @brief convert Euler angle vector including +-2pi to 0 jump to continuous series data
  69. * @param [inout] angle_vector input angle vector
  70. */
  71. void convertEulerAngleToMonotonic(std::vector<double> & angle_vector);
  72. /**
  73. * @brief calculate the lateral error of the given pose relative to the given reference pose
  74. * @param [in] ego_pose pose to check for error
  75. * @param [in] ref_pose reference pose
  76. * @return lateral distance between the two poses
  77. */
  78. //double calcLateralError(const Pose & ego_pose, const Pose & ref_pose);
  79. double calcLateralError(const iv::ADCPose & ego_pose, const iv::ADCPose & ref_pose);
  80. /**
  81. * @brief convert the given Trajectory msg to a MPCTrajectory object
  82. * @param [in] input trajectory to convert
  83. * @return resulting MPCTrajectory
  84. */
  85. //MPCTrajectory convertToMPCTrajectory(const Trajectory & input);
  86. /**
  87. * @brief convert the given MPCTrajectory to a Trajectory msg
  88. * @param [in] input MPCTrajectory to be converted
  89. * @return output converted Trajectory msg
  90. */
  91. //Trajectory convertToAutowareTrajectory(const MPCTrajectory & input);
  92. /**
  93. * @brief calculate the arc length at each point of the given trajectory
  94. * @param [in] trajectory trajectory for which to calculate the arc length
  95. * @param [out] arc_length the cumulative arc length at each point of the trajectory
  96. */
  97. void calcMPCTrajectoryArcLength(const MPCTrajectory & trajectory, std::vector<double> & arc_length);
  98. /**
  99. * @brief resample the given trajectory with the given fixed interval
  100. * @param [in] input trajectory to resample
  101. * @param [in] resample_interval_dist the desired distance between two successive trajectory points
  102. * @return The pair contains the successful flag and the resultant resampled trajectory
  103. */
  104. std::pair<bool, MPCTrajectory> resampleMPCTrajectoryByDistance(
  105. const MPCTrajectory & input, const double resample_interval_dist, const size_t nearest_seg_idx,
  106. const double ego_offset_to_segment);
  107. /**
  108. * @brief linearly interpolate the given trajectory assuming a base indexing and a new desired
  109. * indexing
  110. * @param [in] in_index indexes for each trajectory point
  111. * @param [in] in_traj MPCTrajectory to interpolate
  112. * @param [in] out_index desired interpolated indexes
  113. * @param [out] out_traj resulting interpolated MPCTrajectory
  114. */
  115. bool linearInterpMPCTrajectory(
  116. const std::vector<double> & in_index, const MPCTrajectory & in_traj,
  117. const std::vector<double> & out_index, MPCTrajectory & out_traj);
  118. /**
  119. * @brief fill the relative_time field of the given MPCTrajectory
  120. * @param [in] traj MPCTrajectory for which to fill in the relative_time
  121. * @return true if the calculation was successful
  122. */
  123. bool calcMPCTrajectoryTime(MPCTrajectory & traj);
  124. /**
  125. * @brief recalculate the velocity field (vx) of the MPCTrajectory with dynamic smoothing
  126. * @param [in] start_seg_idx segment index of the trajectory point from which to start smoothing
  127. * @param [in] start_vel initial velocity to set at the start_seg_idx
  128. * @param [in] acc_lim limit on the acceleration
  129. * @param [in] tau constant to control the smoothing (high-value = very smooth)
  130. * @param [inout] traj MPCTrajectory for which to calculate the smoothed velocity
  131. */
  132. void dynamicSmoothingVelocity(
  133. const size_t start_seg_idx, const double start_vel, const double acc_lim, const double tau,
  134. MPCTrajectory & traj);
  135. /**
  136. * @brief calculate yaw angle in MPCTrajectory from xy vector
  137. * @param [inout] traj object trajectory
  138. * @param [in] shift is forward or not
  139. */
  140. void calcTrajectoryYawFromXY(MPCTrajectory & traj, const bool is_forward_shift);
  141. /**
  142. * @brief Calculate path curvature by 3-points circle fitting with smoothing num (use nearest 3
  143. * points when num = 1)
  144. * @param [in] curvature_smoothing_num_traj index distance for 3 points for curvature calculation
  145. * @param [in] curvature_smoothing_num_ref_steer index distance for 3 points for smoothed curvature
  146. * calculation
  147. * @param [inout] traj object trajectory
  148. */
  149. void calcTrajectoryCurvature(
  150. const int curvature_smoothing_num_traj, const int curvature_smoothing_num_ref_steer,
  151. MPCTrajectory & traj);
  152. /**
  153. * @brief Calculate path curvature by 3-points circle fitting with smoothing num (use nearest 3
  154. * points when num = 1)
  155. * @param [in] curvature_smoothing_num index distance for 3 points for curvature calculation
  156. * @param [in] traj input trajectory
  157. * @return vector of curvatures at each point of the given trajectory
  158. */
  159. std::vector<double> calcTrajectoryCurvature(
  160. const int curvature_smoothing_num, const MPCTrajectory & traj);
  161. /**
  162. * @brief calculate nearest pose on MPCTrajectory with linear interpolation
  163. * @param [in] traj reference trajectory
  164. * @param [in] self_pose object pose
  165. * @param [out] nearest_pose nearest pose on path
  166. * @param [out] nearest_index path index of nearest pose
  167. * @param [out] nearest_time time of nearest pose on trajectory
  168. * @return false when nearest pose couldn't find for some reasons
  169. */
  170. bool calcNearestPoseInterp(
  171. const MPCTrajectory & traj, const iv::ADCPose & self_pose, iv::ADCPose * nearest_pose, size_t * nearest_index,
  172. double * nearest_time, const double max_dist, const double max_yaw);
  173. /**
  174. * @brief calculate distance to stopped point
  175. */
  176. //double calcStopDistance(const Trajectory & current_trajectory, const int origin);
  177. double calcStopDistance(const MPCTrajectory & current_trajectory, const int origin);
  178. /**
  179. * @brief extend terminal points
  180. * Note: The current MPC does not properly take into account the attitude angle at the end of the
  181. * path. By extending the end of the path in the attitude direction, the MPC can consider the
  182. * attitude angle well, resulting in improved control performance. If the trajectory is
  183. * well-defined considering the end point attitude angle, this feature is not necessary.
  184. * @param [in] terminal yaw
  185. * @param [in] extend interval
  186. * @param [in] flag of forward shift
  187. * @param [out] extended trajectory
  188. */
  189. void extendTrajectoryInYawDirection(
  190. const double yaw, const double interval, const bool is_forward_shift, MPCTrajectory & traj);
  191. /**
  192. * @brief Updates the value of a parameter with the given name.
  193. * @tparam T The type of the parameter value.
  194. * @param parameters A vector of rclcpp::Parameter objects.
  195. * @param name The name of the parameter to update.
  196. * @param value A reference variable to store the updated parameter value.
  197. */
  198. //template <typename T>
  199. //void update_param(
  200. // const std::vector<rclcpp::Parameter> & parameters, const std::string & name, T & value)
  201. //{
  202. // auto it = std::find_if(
  203. // parameters.cbegin(), parameters.cend(),
  204. // [&name](const rclcpp::Parameter & parameter) { return parameter.get_name() == name; });
  205. // if (it != parameters.cend()) {
  206. // value = static_cast<T>(it->template get_value<T>());
  207. // }
  208. //}
  209. } // namespace MPCUtils
  210. } // namespace autoware::motion::control::mpc_lateral_controller
  211. #endif // MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_