Skip to content

Commit

Permalink
fix(pid_longitudinal_controller): add virtual last point to avoid wro…
Browse files Browse the repository at this point in the history
…ng find wrong nearest_idx

Signed-off-by: Berkay Karaman <[email protected]>
  • Loading branch information
brkay54 committed Dec 5, 2023
1 parent 4842216 commit cc4a4f6
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,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 getExtendTrajectoryPoint(
const double extend_distance, const TrajectoryPoint & goal_point);

} // namespace longitudinal_utils
} // namespace autoware::motion::control::pid_longitudinal_controller

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -196,5 +196,23 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
}
return p;
}

TrajectoryPoint getExtendTrajectoryPoint(
const double extend_distance, const TrajectoryPoint & goal_point)
{
const auto extend_pose =
tier4_autoware_utils::calcOffsetPose(goal_point.pose, extend_distance, 0.0, 0.0);

TrajectoryPoint extend_trajectory_point;
extend_trajectory_point.pose = extend_pose;
// TODO[someone]: Transform functions creates point at inverse Z direction for non-zero pitch
// value
extend_trajectory_point.pose.position.z = 2 * goal_point.pose.position.z - extend_pose.position.z;
extend_trajectory_point.longitudinal_velocity_mps = goal_point.longitudinal_velocity_mps;
extend_trajectory_point.lateral_velocity_mps = goal_point.lateral_velocity_mps;
extend_trajectory_point.acceleration_mps2 = goal_point.acceleration_mps2;
return extend_trajectory_point;
}

} // namespace longitudinal_utils
} // namespace autoware::motion::control::pid_longitudinal_controller
Original file line number Diff line number Diff line change
Expand Up @@ -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::getExtendTrajectoryPoint(
virtual_point_distance, m_trajectory.points.back()));
}

rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallback(
Expand Down

0 comments on commit cc4a4f6

Please sign in to comment.