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

fix(obstacle_avoidance_planner): change behavior when optimization fails #1575

Closed
wants to merge 1 commit 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
10 changes: 7 additions & 3 deletions planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -471,8 +471,13 @@

const auto get_prev_optimized_traj_points = [&]() {
if (prev_optimized_traj_points_ptr_) {
RCLCPP_WARN(logger_, "return the previous optimized_trajectory as exceptional behavior.");
return *prev_optimized_traj_points_ptr_;
}
RCLCPP_WARN(
logger_,
"Try to return the previous optimized_trajectory as exceptional behavior, "
"but this failure also. Then retrun path_smoother output.");

Check warning on line 480 in planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (retrun)

Check warning on line 480 in planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (retrun)
return smoothed_points;
};

Expand All @@ -499,16 +504,15 @@
// 6. optimize steer angles
const auto optimized_variables = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat);
if (!optimized_variables) {
RCLCPP_INFO_EXPRESSION(
logger_, enable_debug_info_, "return std::nullopt since could not solve qp");
RCLCPP_WARN(logger_, "return std::nullopt since could not solve qp");
return get_prev_optimized_traj_points();
}

// 7. convert to points with validation
const auto mpt_traj_points = calcMPTPoints(ref_points, *optimized_variables, mpt_mat);
if (!mpt_traj_points) {
RCLCPP_WARN(logger_, "return std::nullopt since lateral or yaw error is too large.");
return get_prev_optimized_traj_points();
return smoothed_points;
}

// 8. publish trajectories for debug
Expand Down
Loading