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(obstacle_avoidance_planner): not only yaw thresh but also dist thresh for find nearest index #1037

Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -296,7 +296,7 @@ class MPTOptimizer

size_t findNearestIndexWithSoftYawConstraints(
const std::vector<geometry_msgs::msg::Point> & points, const geometry_msgs::msg::Pose & pose,
const double yaw_threshold) const;
const double dist_threshold, const double yaw_threshold) const;

public:
MPTOptimizer(
Expand Down
9 changes: 6 additions & 3 deletions planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -430,6 +430,7 @@ void MPTOptimizer::calcPlanningFromEgo(std::vector<ReferencePoint> & ref_points)
// assign fix kinematics
const size_t nearest_ref_idx = findNearestIndexWithSoftYawConstraints(
points_utils::convertToPoints(ref_points), current_ego_pose_,
traj_param_.delta_dist_threshold_for_closest_point,
traj_param_.delta_yaw_threshold_for_closest_point);

// calculate cropped_ref_points.at(nearest_ref_idx) with yaw
Expand Down Expand Up @@ -468,6 +469,7 @@ std::vector<ReferencePoint> MPTOptimizer::getFixedReferencePoints(
const auto & prev_ref_points = prev_trajs->mpt_ref_points;
const int nearest_prev_ref_idx = static_cast<int>(findNearestIndexWithSoftYawConstraints(
points_utils::convertToPoints(prev_ref_points), current_ego_pose_,
traj_param_.delta_dist_threshold_for_closest_point,
traj_param_.delta_yaw_threshold_for_closest_point));

// calculate begin_prev_ref_idx
Expand Down Expand Up @@ -1222,12 +1224,12 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> MPTOptimizer::get

size_t MPTOptimizer::findNearestIndexWithSoftYawConstraints(
const std::vector<geometry_msgs::msg::Point> & points, const geometry_msgs::msg::Pose & pose,
const double yaw_threshold) const
const double dist_threshold, const double yaw_threshold) const
{
const auto points_with_yaw = points_utils::convertToPosesWithYawEstimation(points);

const auto nearest_idx_optional = tier4_autoware_utils::findNearestIndex(
points_with_yaw, pose, std::numeric_limits<double>::max(), yaw_threshold);
const auto nearest_idx_optional =
tier4_autoware_utils::findNearestIndex(points_with_yaw, pose, dist_threshold, yaw_threshold);
return nearest_idx_optional
? *nearest_idx_optional
: tier4_autoware_utils::findNearestIndex(points_with_yaw, pose.position);
Expand Down Expand Up @@ -1330,6 +1332,7 @@ void MPTOptimizer::calcExtraPoints(
points_utils::convertToPosesWithYawEstimation(points_utils::convertToPoints(ref_points));
const size_t prev_idx = findNearestIndexWithSoftYawConstraints(
points_utils::convertToPoints(prev_ref_points), ref_points_with_yaw.at(i),
traj_param_.delta_dist_threshold_for_closest_point,
traj_param_.delta_yaw_threshold_for_closest_point);
const double dist_to_nearest_prev_ref =
tier4_autoware_utils::calcDistance2d(prev_ref_points.at(prev_idx), ref_points.at(i));
Expand Down
9 changes: 5 additions & 4 deletions planning/obstacle_avoidance_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,12 +203,12 @@ std::tuple<std::vector<double>, std::vector<double>> calcVehicleCirclesInfo(

size_t findNearestIndexWithSoftYawConstraints(
const std::vector<geometry_msgs::msg::Point> & points, const geometry_msgs::msg::Pose & pose,
const double yaw_threshold)
const double dist_threshold, const double yaw_threshold)
{
const auto points_with_yaw = points_utils::convertToPosesWithYawEstimation(points);

const auto nearest_idx_optional = tier4_autoware_utils::findNearestIndex(
points_with_yaw, pose, std::numeric_limits<double>::max(), yaw_threshold);
const auto nearest_idx_optional =
tier4_autoware_utils::findNearestIndex(points_with_yaw, pose, dist_threshold, yaw_threshold);
return nearest_idx_optional
? *nearest_idx_optional
: tier4_autoware_utils::findNearestIndex(points_with_yaw, pose.position);
Expand Down Expand Up @@ -1083,6 +1083,7 @@ void ObstacleAvoidancePlanner::calcVelocity(
for (size_t i = 0; i < traj_points.size(); i++) {
const size_t nearest_path_idx = findNearestIndexWithSoftYawConstraints(
points_utils::convertToPoints(path_points), traj_points.at(i).pose,
traj_param_.delta_dist_threshold_for_closest_point,
traj_param_.delta_yaw_threshold_for_closest_point);
const size_t second_nearest_path_idx = [&]() -> size_t {
if (nearest_path_idx == 0) {
Expand Down Expand Up @@ -1464,7 +1465,7 @@ ObstacleAvoidancePlanner::alignVelocity(

const auto & target_pose = fine_traj_points_with_vel[i].pose;
const auto closest_seg_idx_optional = tier4_autoware_utils::findNearestSegmentIndex(
truncated_points, target_pose, std::numeric_limits<double>::max(),
truncated_points, target_pose, traj_param_.delta_dist_threshold_for_closest_point,
traj_param_.delta_yaw_threshold_for_closest_point);

const auto closest_seg_idx =
Expand Down