Skip to content

Commit 2b7d88f

Browse files
update
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 16a71ce commit 2b7d88f

File tree

3 files changed

+2
-3
lines changed

3 files changed

+2
-3
lines changed

planning/behavior_path_start_planner_module/config/start_planner.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
th_stopped_velocity: 0.01
77
th_stopped_time: 1.0
88
objects_collision_check_margins: [2.0, 1.0, 0.5, 0.1]
9-
back_objects_collision_check_margin: 3.0
9+
back_objects_collision_check_margin: 0.5
1010
collision_check_margin_from_front_object: 5.0
1111
th_moving_object_velocity: 1.0
1212
th_distance_to_middle_of_the_road: 0.5

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,6 @@ Pose getBackedPose(
6767
* lanelets. It compares each corner of the vehicle's transformed footprint with every corner of
6868
* object polygons to find the shortest distance within the lanelet system.
6969
*/
70-
7170
double calcMinArcLengthDistanceFromEgoToObjects(
7271
const tier4_autoware_utils::LinearRing2d & local_vehicle_footprint, const Pose & ego_pose,
7372
const lanelet::ConstLanelets & lanelets, const PredictedObjects & static_objects);

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1007,7 +1007,7 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
10071007
if (
10081008
(start_planner_utils::calcMinArcLengthDistanceFromEgoToObjects(
10091009
local_vehicle_footprint, *backed_pose, pull_out_lanes,
1010-
back_stop_objects_in_pull_out_lanes) > parameters_->back_objects_collision_check_margin) &&
1010+
back_stop_objects_in_pull_out_lanes) < parameters_->back_objects_collision_check_margin) ||
10111011
(utils::checkCollisionBetweenFootprintAndObjects(
10121012
local_vehicle_footprint, *backed_pose, back_stop_objects_in_pull_out_lanes,
10131013
parameters_->objects_collision_check_margins.back()))) {

0 commit comments

Comments
 (0)