Skip to content

Commit

Permalink
feat(behavior_path_planner): parametrize avoidance target type (tier4…
Browse files Browse the repository at this point in the history
…#574)

* parametrize avoidance target type

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* add target type parameter in yaml

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* mototbike -> motorcycle

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* apply clang

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
  • Loading branch information
TakaHoribe authored and boyali committed Sep 28, 2022
1 parent b2d031f commit 0668094
Show file tree
Hide file tree
Showing 5 changed files with 51 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,5 +46,16 @@
longitudinal_collision_margin_min_distance: 0.0 # [m]
longitudinal_collision_margin_time: 0.0

# avoidance is performed for the object type with true
target_object:
car: true
truck: true
bus: true
trailer: true
unknown: false
bicycle: false
motorcycle: false
pedestrian: false

# ---------- advanced parameters ----------
avoidance_execution_lateral_threshold: 0.499
Original file line number Diff line number Diff line change
Expand Up @@ -46,5 +46,16 @@
longitudinal_collision_margin_min_distance: 0.0 # [m]
longitudinal_collision_margin_time: 0.0

# avoidance is performed for the object type with true
target_object:
car: true
truck: true
bus: true
trailer: true
unknown: false
bicycle: false
motorcycle: false
pedestrian: false

# ---------- advanced parameters ----------
avoidance_execution_lateral_threshold: 0.499
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,18 @@ struct AvoidanceParameters
// avoidance path will be generated unless their lateral margin difference exceeds this value.
double avoidance_execution_lateral_threshold;

// true by default
bool avoid_car{true}; // avoidance is performed for type object car
bool avoid_truck{true}; // avoidance is performed for type object truck
bool avoid_bus{true}; // avoidance is performed for type object bus
bool avoid_trailer{true}; // avoidance is performed for type object trailer

// false by default
bool avoid_unknown{false}; // avoidance is performed for type object unknown
bool avoid_bicycle{false}; // avoidance is performed for type object bicycle
bool avoid_motorcycle{false}; // avoidance is performed for type object motorbike
bool avoid_pedestrian{false}; // avoidance is performed for type object pedestrian

// debug
bool publish_debug_marker = false;
bool print_debug_info = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,15 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam()
p.publish_debug_marker = dp("publish_debug_marker", false);
p.print_debug_info = dp("print_debug_info", false);

p.avoid_car = dp("target_object.car", true);
p.avoid_truck = dp("target_object.truck", true);
p.avoid_bus = dp("target_object.bus", true);
p.avoid_trailer = dp("target_object.trailer", true);
p.avoid_unknown = dp("target_object.unknown", false);
p.avoid_bicycle = dp("target_object.bicycle", false);
p.avoid_motorcycle = dp("target_object.motorcycle", false);
p.avoid_pedestrian = dp("target_object.pedestrian", false);

p.avoidance_execution_lateral_threshold = dp("avoidance_execution_lateral_threshold", 0.499);

return p;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2528,8 +2528,14 @@ bool AvoidanceModule::isTargetObjectType(const PredictedObject & object) const
using autoware_auto_perception_msgs::msg::ObjectClassification;
const auto t = util::getHighestProbLabel(object.classification);
const auto is_object_type =
(t == ObjectClassification::CAR || t == ObjectClassification::TRUCK ||
t == ObjectClassification::BUS);
((t == ObjectClassification::CAR && parameters_.avoid_car) ||
(t == ObjectClassification::TRUCK && parameters_.avoid_truck) ||
(t == ObjectClassification::BUS && parameters_.avoid_bus) ||
(t == ObjectClassification::TRAILER && parameters_.avoid_trailer) ||
(t == ObjectClassification::UNKNOWN && parameters_.avoid_unknown) ||
(t == ObjectClassification::BICYCLE && parameters_.avoid_bicycle) ||
(t == ObjectClassification::MOTORCYCLE && parameters_.avoid_motorcycle) ||
(t == ObjectClassification::PEDESTRIAN && parameters_.avoid_pedestrian));
return is_object_type;
}

Expand Down

0 comments on commit 0668094

Please sign in to comment.