-
Notifications
You must be signed in to change notification settings - Fork 706
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(goal_planner): use precise distance to objects for sorting candidate paths #10296
base: main
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
|
@@ -41,6 +41,7 @@ | |||||
namespace bg = boost::geometry; | ||||||
|
||||||
using autoware::motion_utils::calcLongitudinalOffsetPoint; | ||||||
using autoware::motion_utils::calcLongitudinalOffsetPose; | ||||||
using autoware::motion_utils::calcLongitudinalOffsetToSegment; | ||||||
using autoware::motion_utils::findNearestIndex; | ||||||
using autoware::motion_utils::findNearestSegmentIndex; | ||||||
|
@@ -774,8 +775,9 @@ | |||||
} | ||||||
|
||||||
std::pair<bool, bool> checkObjectsCollisionRough( | ||||||
const PathWithLaneId & path, const PredictedObjects & objects, const double margin, | ||||||
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point) | ||||||
const PathWithLaneId & path, const PredictedObjects & objects, const double min_margin_threshold, | ||||||
const double max_margin_threshold, const BehaviorPathPlannerParameters & parameters, | ||||||
const bool use_offset_ego_point) | ||||||
{ | ||||||
const auto & points = path.points; | ||||||
|
||||||
|
@@ -815,10 +817,10 @@ | |||||
const double min_distance = distance - object_max_length - ego_max_length; | ||||||
const double max_distance = distance - object_min_length - ego_min_length; | ||||||
|
||||||
if (min_distance < margin) { | ||||||
if (min_distance < min_margin_threshold) { | ||||||
has_collision.first = true; | ||||||
} | ||||||
if (max_distance < margin) { | ||||||
if (max_distance < max_margin_threshold) { | ||||||
has_collision.second = true; | ||||||
} | ||||||
} | ||||||
|
@@ -877,6 +879,40 @@ | |||||
return min_distance; | ||||||
} | ||||||
|
||||||
double calculate_distance_to_objects_from_path( | ||||||
Check warning on line 882 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
const PathWithLaneId & path, const PredictedObjects & objects, | ||||||
const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_pose) | ||||||
|
||||||
{ | ||||||
const auto & p = parameters; | ||||||
double min_distance = std::numeric_limits<double>::max(); | ||||||
Check warning on line 888 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
for (const auto & object : objects.objects) { | ||||||
const auto & object_point = object.kinematics.initial_pose_with_covariance.pose.position; | ||||||
Check warning on line 890 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
|
||||||
const auto ego_pose = std::invoke([&]() -> Pose { | ||||||
Check warning on line 892 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
if (use_offset_ego_pose) { | ||||||
const size_t nearest_segment_idx = findNearestSegmentIndex(path.points, object_point); | ||||||
const double offset_length = | ||||||
calcLongitudinalOffsetToSegment(path.points, nearest_segment_idx, object_point); | ||||||
Check warning on line 896 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
const auto ego_pose_opt = | ||||||
calcLongitudinalOffsetPose(path.points, nearest_segment_idx, offset_length); | ||||||
if (ego_pose_opt.has_value()) return ego_pose_opt.value(); | ||||||
} | ||||||
const auto ego_nearest_idx = findNearestIndex(path.points, object_point); | ||||||
return path.points.at(ego_nearest_idx).point.pose; | ||||||
Check warning on line 902 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
}); | ||||||
|
||||||
const auto ego_footprint = | ||||||
autoware_utils::to_footprint(ego_pose, p.base_link2front, p.base_link2rear, p.vehicle_width); | ||||||
Check warning on line 906 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
|
||||||
const double distance = | ||||||
boost::geometry::distance(ego_footprint, autoware_utils::to_polygon2d(object)); | ||||||
min_distance = std::min(min_distance, distance); | ||||||
} | ||||||
Check warning on line 911 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
|
||||||
return min_distance; | ||||||
Check warning on line 913 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
|
||||||
} | ||||||
|
||||||
autoware_internal_planning_msgs::msg::SafetyFactorArray to_safety_factor_array( | ||||||
const CollisionCheckDebugMap & debug_map) | ||||||
{ | ||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
英語の文法を分かりやすくして下さい
"threshold for collision check when the minimum distance between ego"