Skip to content

Commit

Permalink
feat(pull_out): change pull out finish deviation threshould
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Jun 7, 2023
1 parent 35bc65a commit 73265f4
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -685,13 +685,13 @@ bool PullOutModule::hasFinishedPullOut() const
// 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.5;
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.5;
constexpr double yaw_deviation_threshold = 0.087; // 5deg
if (std::abs(yaw_deviation) > yaw_deviation_threshold) {
return false;
}
Expand Down

0 comments on commit 73265f4

Please sign in to comment.