Skip to content

Commit

Permalink
feat(behavior_path_planner): remove lateral offset check for finish s…
Browse files Browse the repository at this point in the history
…tart planner

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Jun 9, 2023
1 parent fc08b4f commit 9302daa
Showing 1 changed file with 0 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -682,21 +682,6 @@ bool StartPlannerModule::hasFinishedPullOut() const

const auto current_pose = planner_data_->self_odometry->pose.pose;

// keep running until returning to the path, considering that other modules (e.g avoidance)
// are also running at the same time.
const double lateral_offset_to_path =
motion_utils::calcLateralOffset(getCurrentPath().points, current_pose.position);
constexpr double lateral_offset_threshold = 0.2;
if (std::abs(lateral_offset_to_path) > lateral_offset_threshold) {
return false;
}
const double yaw_deviation =
motion_utils::calcYawDeviation(getCurrentPath().points, current_pose);
constexpr double yaw_deviation_threshold = 0.087; // 5deg
if (std::abs(yaw_deviation) > yaw_deviation_threshold) {
return false;
}

// check that ego has passed pull out end point
const auto arclength_current =
lanelet::utils::getArcCoordinates(status_.current_lanes, current_pose);
Expand Down

0 comments on commit 9302daa

Please sign in to comment.