Skip to content

Commit ca20c93

Browse files
committed
feat(avoidance): wait and see ambiguous stopped vehicle (autowarefoundation#6631)
* feat(avoidance): wait and see the ambiguous stopped vehicle Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): wait and see objects around ego straight lane Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * tmp Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor(avoidance): filtering logic for vehicle type objects Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): wait with unsafe avoidance path Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): use getRightLanelet Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor(avoidance): parameterize Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 5b597a7 commit ca20c93

File tree

8 files changed

+186
-83
lines changed

8 files changed

+186
-83
lines changed

planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -133,10 +133,13 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
133133

134134
{
135135
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
136-
p.enable_force_avoidance_for_stopped_vehicle =
137-
getOrDeclareParameter<bool>(*node, ns + "enable");
138-
p.threshold_time_force_avoidance_for_stopped_vehicle =
139-
getOrDeclareParameter<double>(*node, ns + "time_threshold");
136+
p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter<bool>(*node, ns + "enable");
137+
p.closest_distance_to_wait_and_see_for_ambiguous_vehicle =
138+
getOrDeclareParameter<double>(*node, ns + "closest_distance_to_wait_and_see");
139+
p.time_threshold_for_ambiguous_vehicle =
140+
getOrDeclareParameter<double>(*node, ns + "condition.time_threshold");
141+
p.distance_threshold_for_ambiguous_vehicle =
142+
getOrDeclareParameter<double>(*node, ns + "condition.distance_threshold");
140143
p.object_ignore_section_traffic_light_in_front_distance =
141144
getOrDeclareParameter<double>(*node, ns + "ignore_area.traffic_light.front_distance");
142145
p.object_ignore_section_crosswalk_in_front_distance =

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+4-2
Original file line numberDiff line numberDiff line change
@@ -156,8 +156,10 @@
156156
# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
157157
avoidance_for_ambiguous_vehicle:
158158
enable: false # [-]
159-
time_threshold: 1.0 # [s]
160-
distance_threshold: 1.0 # [m]
159+
closest_distance_to_wait_and_see: 10.0 # [m]
160+
condition:
161+
time_threshold: 1.0 # [s]
162+
distance_threshold: 1.0 # [m]
161163
ignore_area:
162164
traffic_light:
163165
front_distance: 100.0 # [m]

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ struct AvoidanceParameters
100100
bool enable_cancel_maneuver{false};
101101

102102
// enable avoidance for all parking vehicle
103-
bool enable_force_avoidance_for_stopped_vehicle{false};
103+
bool enable_avoidance_for_ambiguous_vehicle{false};
104104

105105
// enable yield maneuver.
106106
bool enable_yield_maneuver{false};
@@ -184,8 +184,9 @@ struct AvoidanceParameters
184184
double object_check_min_road_shoulder_width{0.0};
185185

186186
// force avoidance
187-
double threshold_time_force_avoidance_for_stopped_vehicle{0.0};
188-
double force_avoidance_distance_threshold{0.0};
187+
double closest_distance_to_wait_and_see_for_ambiguous_vehicle{0.0};
188+
double time_threshold_for_ambiguous_vehicle{0.0};
189+
double distance_threshold_for_ambiguous_vehicle{0.0};
189190

190191
// when complete avoidance motion, there is a distance margin with the object
191192
// for longitudinal direction

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+29
Original file line numberDiff line numberDiff line change
@@ -289,6 +289,35 @@ class AvoidanceHelper
289289
});
290290
}
291291

292+
bool isReady(const ObjectDataArray & objects) const
293+
{
294+
if (objects.empty()) {
295+
return true;
296+
}
297+
298+
const auto object = objects.front();
299+
300+
if (!object.is_ambiguous) {
301+
return true;
302+
}
303+
304+
if (!object.avoid_margin.has_value()) {
305+
return true;
306+
}
307+
308+
const auto is_object_on_right = utils::avoidance::isOnRight(object);
309+
const auto desire_shift_length =
310+
getShiftLength(object, is_object_on_right, object.avoid_margin.value());
311+
312+
const auto prepare_distance = getMinimumPrepareDistance();
313+
const auto constant_distance = getFrontConstantDistance(object);
314+
const auto avoidance_distance = getMinAvoidanceDistance(desire_shift_length);
315+
316+
return object.longitudinal <
317+
prepare_distance + constant_distance + avoidance_distance +
318+
parameters_->closest_distance_to_wait_and_see_for_ambiguous_vehicle;
319+
}
320+
292321
bool isReady(const AvoidLineArray & new_shift_lines, const double current_shift_length) const
293322
{
294323
if (std::abs(current_shift_length) < 1e-3) {

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -138,12 +138,13 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
138138

139139
{
140140
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
141-
p.enable_force_avoidance_for_stopped_vehicle =
142-
getOrDeclareParameter<bool>(*node, ns + "enable");
143-
p.threshold_time_force_avoidance_for_stopped_vehicle =
144-
getOrDeclareParameter<double>(*node, ns + "time_threshold");
145-
p.force_avoidance_distance_threshold =
146-
getOrDeclareParameter<double>(*node, ns + "distance_threshold");
141+
p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter<bool>(*node, ns + "enable");
142+
p.closest_distance_to_wait_and_see_for_ambiguous_vehicle =
143+
getOrDeclareParameter<double>(*node, ns + "closest_distance_to_wait_and_see");
144+
p.time_threshold_for_ambiguous_vehicle =
145+
getOrDeclareParameter<double>(*node, ns + "condition.time_threshold");
146+
p.distance_threshold_for_ambiguous_vehicle =
147+
getOrDeclareParameter<double>(*node, ns + "condition.distance_threshold");
147148
p.object_ignore_section_traffic_light_in_front_distance =
148149
getOrDeclareParameter<double>(*node, ns + "ignore_area.traffic_light.front_distance");
149150
p.object_ignore_section_crosswalk_in_front_distance =

planning/behavior_path_avoidance_module/src/debug.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -579,6 +579,8 @@ MarkerArray createDebugMarkerArray(
579579
addObjects(data.other_objects, std::string("ParallelToEgoLane"));
580580
addObjects(data.other_objects, std::string("MergingToEgoLane"));
581581
addObjects(data.other_objects, std::string("UnstableObject"));
582+
addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle"));
583+
addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle(wait-and-see)"));
582584
}
583585

584586
// shift line pre-process

planning/behavior_path_avoidance_module/src/scene.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -513,7 +513,8 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de
513513
*/
514514
data.comfortable = helper_->isComfortable(data.new_shift_line);
515515
data.safe = isSafePath(data.candidate_path, debug);
516-
data.ready = helper_->isReady(data.new_shift_line, path_shifter_.getLastShiftLength());
516+
data.ready = helper_->isReady(data.new_shift_line, path_shifter_.getLastShiftLength()) &&
517+
helper_->isReady(data.target_objects);
517518
}
518519

519520
void AvoidanceModule::fillEgoStatus(

planning/behavior_path_avoidance_module/src/utils.cpp

+131-67
Original file line numberDiff line numberDiff line change
@@ -492,7 +492,8 @@ bool isMergingToEgoLane(const ObjectData & object)
492492
}
493493

494494
bool isParkedVehicle(
495-
ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
495+
ObjectData & object, const AvoidancePlanningData & data,
496+
const std::shared_ptr<RouteHandler> & route_handler,
496497
const std::shared_ptr<AvoidanceParameters> & parameters)
497498
{
498499
using lanelet::geometry::distance2d;
@@ -589,57 +590,36 @@ bool isParkedVehicle(
589590
object.shiftable_ratio > parameters->object_check_shiftable_ratio;
590591
}
591592

592-
return is_left_side_parked_vehicle || is_right_side_parked_vehicle;
593-
}
594-
595-
bool isAmbiguousStoppedVehicle(
596-
ObjectData & object, const AvoidancePlanningData & data,
597-
const std::shared_ptr<const PlannerData> & planner_data,
598-
const std::shared_ptr<AvoidanceParameters> & parameters)
599-
{
600-
const auto stop_time_longer_than_threshold =
601-
object.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle;
602-
603-
if (!stop_time_longer_than_threshold) {
593+
if (!is_left_side_parked_vehicle && !is_right_side_parked_vehicle) {
604594
return false;
605595
}
606596

607597
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
608-
const auto is_moving_distance_longer_than_threshold =
609-
tier4_autoware_utils::calcDistance2d(object.init_pose, object_pose) >
610-
parameters->force_avoidance_distance_threshold;
611-
612-
if (is_moving_distance_longer_than_threshold) {
613-
return false;
614-
}
615-
616-
if (object.is_within_intersection) {
617-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is in the intersection area.");
618-
return false;
619-
}
620-
621-
const auto rh = planner_data->route_handler;
622-
623-
if (
624-
!!rh->getRoutingGraphPtr()->right(object.overhang_lanelet) &&
625-
!!rh->getRoutingGraphPtr()->left(object.overhang_lanelet)) {
626-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane.");
598+
object.to_centerline =
599+
lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance;
600+
if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) {
627601
return false;
628602
}
629603

630-
if (!object.is_on_ego_lane) {
631-
return true;
632-
}
604+
return true;
605+
}
633606

607+
bool isCloseToStopFactor(
608+
ObjectData & object, const AvoidancePlanningData & data,
609+
const std::shared_ptr<const PlannerData> & planner_data,
610+
const std::shared_ptr<AvoidanceParameters> & parameters)
611+
{
612+
const auto & rh = planner_data->route_handler;
634613
const auto & ego_pose = planner_data->self_odometry->pose.pose;
614+
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
635615

636616
// force avoidance for stopped vehicle
637-
bool not_parked_object = true;
617+
bool is_close_to_stop_factor = false;
638618

639619
// check traffic light
640620
const auto to_traffic_light = getDistanceToNextTrafficLight(object_pose, data.extend_lanelets);
641621
{
642-
not_parked_object =
622+
is_close_to_stop_factor =
643623
to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance;
644624
}
645625

@@ -651,12 +631,89 @@ bool isAmbiguousStoppedVehicle(
651631
const auto stop_for_crosswalk =
652632
to_crosswalk < parameters->object_ignore_section_crosswalk_in_front_distance &&
653633
to_crosswalk > -1.0 * parameters->object_ignore_section_crosswalk_behind_distance;
654-
not_parked_object = not_parked_object || stop_for_crosswalk;
634+
is_close_to_stop_factor = is_close_to_stop_factor || stop_for_crosswalk;
655635
}
656636

657637
object.to_stop_factor_distance = std::min(to_traffic_light, to_crosswalk);
658638

659-
return !not_parked_object;
639+
return is_close_to_stop_factor;
640+
}
641+
642+
bool isNeverAvoidanceTarget(
643+
ObjectData & object, const AvoidancePlanningData & data,
644+
const std::shared_ptr<const PlannerData> & planner_data,
645+
const std::shared_ptr<AvoidanceParameters> & parameters)
646+
{
647+
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
648+
const auto is_moving_distance_longer_than_threshold =
649+
tier4_autoware_utils::calcDistance2d(object.init_pose, object_pose) >
650+
parameters->distance_threshold_for_ambiguous_vehicle;
651+
if (is_moving_distance_longer_than_threshold) {
652+
object.reason = AvoidanceDebugFactor::MOVING_OBJECT;
653+
return true;
654+
}
655+
656+
if (object.is_within_intersection) {
657+
if (object.behavior == ObjectData::Behavior::NONE) {
658+
object.reason = "ParallelToEgoLane";
659+
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it.");
660+
return true;
661+
}
662+
663+
if (object.behavior == ObjectData::Behavior::MERGING) {
664+
object.reason = "MergingToEgoLane";
665+
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it.");
666+
return true;
667+
}
668+
}
669+
670+
if (object.is_on_ego_lane) {
671+
if (
672+
planner_data->route_handler->getRightLanelet(object.overhang_lanelet).has_value() &&
673+
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet).has_value()) {
674+
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
675+
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it.");
676+
return true;
677+
}
678+
}
679+
680+
if (isCloseToStopFactor(object, data, planner_data, parameters)) {
681+
if (object.is_on_ego_lane && !object.is_parked) {
682+
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
683+
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is close to stop factor. never avoid it.");
684+
return true;
685+
}
686+
}
687+
688+
return false;
689+
}
690+
691+
bool isObviousAvoidanceTarget(
692+
ObjectData & object, [[maybe_unused]] const AvoidancePlanningData & data,
693+
[[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data,
694+
[[maybe_unused]] const std::shared_ptr<AvoidanceParameters> & parameters)
695+
{
696+
if (!object.is_within_intersection) {
697+
if (object.is_parked && object.behavior == ObjectData::Behavior::NONE) {
698+
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is obvious parked vehicle.");
699+
return true;
700+
}
701+
702+
if (!object.is_on_ego_lane && object.behavior == ObjectData::Behavior::NONE) {
703+
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is adjacent vehicle.");
704+
return true;
705+
}
706+
}
707+
708+
if (!object.is_parked) {
709+
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
710+
}
711+
712+
if (object.behavior == ObjectData::Behavior::MERGING) {
713+
object.reason = "MergingToEgoLane";
714+
}
715+
716+
return false;
660717
}
661718

662719
bool isSatisfiedWithCommonCondition(
@@ -759,50 +816,56 @@ bool isSatisfiedWithVehicleCondition(
759816
{
760817
object.behavior = getObjectBehavior(object, parameters);
761818
object.is_on_ego_lane = isOnEgoLane(object);
762-
object.is_ambiguous = isAmbiguousStoppedVehicle(object, data, planner_data, parameters);
763819

764-
// from here condition check for vehicle type objects.
765-
if (object.is_ambiguous && parameters->enable_force_avoidance_for_stopped_vehicle) {
820+
if (isNeverAvoidanceTarget(object, data, planner_data, parameters)) {
821+
return false;
822+
}
823+
824+
if (isObviousAvoidanceTarget(object, data, planner_data, parameters)) {
766825
return true;
767826
}
768827

769-
// check vehicle shift ratio
770-
if (object.is_on_ego_lane) {
771-
if (object.is_parked) {
772-
return true;
773-
} else {
774-
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
775-
return false;
776-
}
828+
// from here, filtering for ambiguous vehicle.
829+
830+
if (!parameters->enable_avoidance_for_ambiguous_vehicle) {
831+
object.reason = "AmbiguousStoppedVehicle";
832+
return false;
777833
}
778834

779-
// Object is on center line -> ignore.
780-
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
781-
object.to_centerline =
782-
lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance;
783-
if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) {
784-
object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE;
835+
const auto stop_time_longer_than_threshold =
836+
object.stop_time > parameters->time_threshold_for_ambiguous_vehicle;
837+
if (!stop_time_longer_than_threshold) {
838+
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
785839
return false;
786840
}
787841

788842
if (object.is_within_intersection) {
789-
std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else");
790-
if (turn_direction == "straight") {
843+
if (object.behavior == ObjectData::Behavior::DEVIATING) {
844+
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
845+
object.is_ambiguous = true;
846+
return true;
847+
}
848+
} else {
849+
if (object.behavior == ObjectData::Behavior::MERGING) {
850+
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
851+
object.is_ambiguous = true;
791852
return true;
792853
}
793854

794-
if (object.behavior == ObjectData::Behavior::NONE) {
795-
object.reason = "ParallelToEgoLane";
796-
return false;
855+
if (object.behavior == ObjectData::Behavior::DEVIATING) {
856+
object.reason = "AmbiguousStoppedVehicle(wait-and-see)";
857+
object.is_ambiguous = true;
858+
return true;
797859
}
798-
}
799860

800-
if (object.behavior == ObjectData::Behavior::MERGING) {
801-
object.reason = "MergingToEgoLane";
802-
return false;
861+
if (object.behavior == ObjectData::Behavior::NONE) {
862+
object.is_ambiguous = false;
863+
return true;
864+
}
803865
}
804866

805-
return true;
867+
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
868+
return false;
806869
}
807870

808871
bool isNoNeedAvoidanceBehavior(
@@ -1729,7 +1792,8 @@ void filterTargetObjects(
17291792
if (filtering_utils::isVehicleTypeObject(o)) {
17301793
o.is_within_intersection =
17311794
filtering_utils::isWithinIntersection(o, planner_data->route_handler);
1732-
o.is_parked = filtering_utils::isParkedVehicle(o, planner_data->route_handler, parameters);
1795+
o.is_parked =
1796+
filtering_utils::isParkedVehicle(o, data, planner_data->route_handler, parameters);
17331797
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);
17341798

17351799
if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) {

0 commit comments

Comments
 (0)