Skip to content

Commit 4a1706a

Browse files
committed
fix(pid_longitudinal_controller): add virtual last point to avoid wrong find wrong nearest_idx
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 75bca30 commit 4a1706a

File tree

3 files changed

+31
-1
lines changed

3 files changed

+31
-1
lines changed

control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,14 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
158158
const size_t src_idx, const double distance,
159159
const autoware_auto_planning_msgs::msg::Trajectory & trajectory);
160160

161+
/**
162+
* @brief calculates the translated position of the goal point with respect to extend_distance
163+
* @param [in] extend_distance current index
164+
* @param [in] goal_point distance to project
165+
*/
166+
TrajectoryPoint getExtendTrajectoryPoint(
167+
const double extend_distance, const TrajectoryPoint & goal_point);
168+
161169
} // namespace longitudinal_utils
162170
} // namespace autoware::motion::control::pid_longitudinal_controller
163171

control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp

+18
Original file line numberDiff line numberDiff line change
@@ -196,5 +196,23 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
196196
}
197197
return p;
198198
}
199+
200+
TrajectoryPoint getExtendTrajectoryPoint(
201+
const double extend_distance, const TrajectoryPoint & goal_point)
202+
{
203+
const auto extend_pose =
204+
tier4_autoware_utils::calcOffsetPose(goal_point.pose, extend_distance, 0.0, 0.0);
205+
206+
TrajectoryPoint extend_trajectory_point;
207+
extend_trajectory_point.pose = extend_pose;
208+
// TODO[someone]: Transform functions creates point at inverse Z direction for non-zero pitch
209+
// value
210+
extend_trajectory_point.pose.position.z = 2 * goal_point.pose.position.z - extend_pose.position.z;
211+
extend_trajectory_point.longitudinal_velocity_mps = goal_point.longitudinal_velocity_mps;
212+
extend_trajectory_point.lateral_velocity_mps = goal_point.lateral_velocity_mps;
213+
extend_trajectory_point.acceleration_mps2 = goal_point.acceleration_mps2;
214+
return extend_trajectory_point;
215+
}
216+
199217
} // namespace longitudinal_utils
200218
} // namespace autoware::motion::control::pid_longitudinal_controller

control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -241,8 +241,12 @@ void PidLongitudinalController::setTrajectory(
241241
RCLCPP_WARN_THROTTLE(logger_, *clock_, 3000, "Unexpected trajectory size < 2. Ignored.");
242242
return;
243243
}
244-
244+
// If the vehicle pass the last point of trajectory, it causes errors on control_data calculation.
245+
// To handle this, we add a virtual point after the last point.
246+
constexpr double virtual_point_distance = 5.0;
245247
m_trajectory = msg;
248+
m_trajectory.points.push_back(longitudinal_utils::getExtendTrajectoryPoint(
249+
virtual_point_distance, m_trajectory.points.back()));
246250
}
247251

248252
rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallback(

0 commit comments

Comments
 (0)