From df05c22cadba8f8a37a4916d91b8e81004a3fdad Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Thu, 1 Feb 2024 14:15:00 +0300 Subject: [PATCH] fix(pid_longitudinal_controller): add virtual last point to avoid wrong find wrong nearest_idx Signed-off-by: Berkay Karaman --- .../longitudinal_controller_utils.hpp | 8 ++++++ .../src/longitudinal_controller_utils.cpp | 26 +++++++++++++++++++ .../src/pid_longitudinal_controller.cpp | 6 ++++- 3 files changed, 39 insertions(+), 1 deletion(-) diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp index ac4fec8dacb7d..18f97d91b5d17 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp +++ b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp @@ -152,6 +152,14 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance( const size_t src_idx, const double distance, const autoware_auto_planning_msgs::msg::Trajectory & trajectory); +/** + * @brief calculates the translated position of the goal point with respect to extend_distance + * @param [in] extend_distance current index + * @param [in] goal_point distance to project + */ +TrajectoryPoint getExtendedTrajectoryPoint( + const double extend_distance, const Trajectory & trajectory); + } // namespace longitudinal_utils } // namespace autoware::motion::control::pid_longitudinal_controller diff --git a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp b/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp index 28cd6e1824859..7a6bd2732b617 100644 --- a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp +++ b/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp @@ -186,5 +186,31 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance( } return p; } + +TrajectoryPoint getExtendedTrajectoryPoint( + const double extend_distance, const Trajectory & trajectory) +{ + const auto extend_pose = + tier4_autoware_utils::calcOffsetPose(trajectory.points.back().pose, extend_distance, 0.0, 0.0); + + // To avoid 0 slope, extend the point with the same slope as the last two points + const double z_change_ratio = + (trajectory.points.at(trajectory.points.size() - 2).pose.position.z - + trajectory.points.back().pose.position.z) / + tier4_autoware_utils::calcDistance3d( + trajectory.points.at(trajectory.points.size() - 2).pose.position, + trajectory.points.back().pose.position); + TrajectoryPoint extend_trajectory_point; + extend_trajectory_point.pose = extend_pose; + + extend_trajectory_point.pose.position.z = + trajectory.points.back().pose.position.z - extend_distance * z_change_ratio; + extend_trajectory_point.longitudinal_velocity_mps = + trajectory.points.back().longitudinal_velocity_mps; + extend_trajectory_point.lateral_velocity_mps = trajectory.points.back().lateral_velocity_mps; + extend_trajectory_point.acceleration_mps2 = trajectory.points.back().acceleration_mps2; + return extend_trajectory_point; +} + } // namespace longitudinal_utils } // namespace autoware::motion::control::pid_longitudinal_controller diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index b700ac7f29f8a..7ac881e3163a0 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -241,8 +241,12 @@ void PidLongitudinalController::setTrajectory( RCLCPP_WARN_THROTTLE(logger_, *clock_, 3000, "Unexpected trajectory size < 2. Ignored."); return; } - + // If the vehicle pass the last point of trajectory, it causes errors on control_data calculation. + // To handle this, we add a virtual point after the last point. + constexpr double virtual_point_distance = 5.0; m_trajectory = msg; + m_trajectory.points.push_back( + longitudinal_utils::getExtendedTrajectoryPoint(virtual_point_distance, m_trajectory)); } rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallback(