Skip to content

Commit

Permalink
fix bug
Browse files Browse the repository at this point in the history
Signed-off-by: 1222-takeshi <m.takeshi1995@gmail.com>
  • Loading branch information
1222-takeshi committed Oct 27, 2022
1 parent 944f05c commit e40ca7b
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions planning/obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1020,12 +1020,12 @@ geometry_msgs::msg::Point ObstacleCruisePlannerNode::calcNearestCollisionPoint(
const auto front_pos = tier4_autoware_utils::calcOffsetPose(
traj_front_pose, vehicle_info_.max_longitudinal_offset_m, 0.0, 0.0)
.position;
segment_points.at(0) = traj_front_pose.position;
segment_points.at(1) = front_pos;
segment_points.push_back(traj_front_pose.position);
segment_points.push_back(front_pos);
} else {
const size_t seg_idx = first_within_idx - 1;
segment_points.at(0) = extended_traj.points.at(seg_idx).pose.position;
segment_points.at(1) = extended_traj.points.at(seg_idx + 1).pose.position;
segment_points.push_back(extended_traj.points.at(seg_idx).pose.position);
segment_points.push_back(extended_traj.points.at(seg_idx + 1).pose.position);
}

size_t min_idx = 0;
Expand Down

0 comments on commit e40ca7b

Please sign in to comment.