Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(behavior_path_planner): add yaw_dev threshold angle #2126

Closed
wants to merge 4 commits into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -600,7 +600,28 @@ void BehaviorPathPlannerNode::run()
const auto output = bt_manager_->run(planner_data);

// path handling
const auto path = getPath(output, planner_data);
auto path = getPath(output, planner_data);

// check if path orientation is valid
if (!path->points.empty()) {
const auto closest_path_point_idx = findEgoIndex(path->points);
const auto yaw_dev = tier4_autoware_utils::calcYawDeviation(
path->points.at(closest_path_point_idx).point.pose, planner_data->self_pose->pose);

if (std::abs(yaw_dev) > M_PI / 2.0) {
RCLCPP_WARN(
get_logger(), "Path orientation is invalid. Path yaw deviation: %f (deg)",
yaw_dev * 180 / M_PI);
if (planner_data_->prev_output_path->points.empty()) {
return;
} else {
path = planner_data_->prev_output_path;
}
} else {
// update planner data
planner_data_->prev_output_path = path;
}
}

// update planner data
planner_data_->prev_output_path = path;
Expand Down