Skip to content

Commit

Permalink
fix(avoidance): the module ignored merging objects unexpectedly (auto…
Browse files Browse the repository at this point in the history
…warefoundation#6601)

* feat(avoidance): output overhang lanelet

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): avoid merging vehicle if it's NOT on ego lane.

Signed-off-by: satoshi-ota <[email protected]>

* fix(avoidance): add flag to identify ambiguous vehicle

Signed-off-by: satoshi-ota <[email protected]>

* refactor(avoidance): add helper function

Signed-off-by: satoshi-ota <[email protected]>

* refactor(avoidance): rename param

Signed-off-by: satoshi-ota <[email protected]>

* chore(avoidance): update comment

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed Apr 2, 2024
1 parent 60f8a99 commit 320bb77
Show file tree
Hide file tree
Showing 9 changed files with 96 additions and 60 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
}

{
const std::string ns = "avoidance.target_filtering.force_avoidance.";
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_force_avoidance_for_stopped_vehicle =
getOrDeclareParameter<bool>(*node, ns + "enable");
p.threshold_time_force_avoidance_for_stopped_vehicle =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@
backward_distance: 10.0 # [m]

# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
force_avoidance:
avoidance_for_ambiguous_vehicle:
enable: false # [-]
time_threshold: 1.0 # [s]
distance_threshold: 1.0 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -384,7 +384,8 @@ struct ObjectData // avoidance target
rclcpp::Time last_move;
double stop_time{0.0};

// store the information of the lanelet which the object's overhang is currently occupying
// It is one of the ego driving lanelets (closest lanelet to the object) and used in the logic to
// check whether the object is on the ego lane.
lanelet::ConstLanelet overhang_lanelet;

// the position at the detected moment
Expand Down Expand Up @@ -420,6 +421,12 @@ struct ObjectData // avoidance target
// is parked vehicle on road shoulder
bool is_parked{false};

// is driving on ego current lane
bool is_on_ego_lane{false};

// is ambiguous stopped vehicle.
bool is_ambiguous{false};

// object direction.
Direction direction{Direction::NONE};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include "behavior_path_avoidance_module/data_structs.hpp"
#include "behavior_path_avoidance_module/utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"

#include <motion_utils/distance/distance.hpp>

Expand Down Expand Up @@ -143,6 +144,24 @@ class AvoidanceHelper
shift_length, getLateralMaxJerkLimit(), getAvoidanceEgoSpeed());
}

double getFrontConstantDistance(const ObjectData & object) const
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
: 0.0;
return object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal;
}

double getRearConstantDistance(const ObjectData & object) const
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
return object_parameter.safety_buffer_longitudinal + data_->parameters.base_link2rear +
object.length;
}

double getEgoShift() const
{
validate();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
}

{
const std::string ns = "avoidance.target_filtering.force_avoidance.";
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_force_avoidance_for_stopped_vehicle =
getOrDeclareParameter<bool>(*node, ns + "enable");
p.threshold_time_force_avoidance_for_stopped_vehicle =
Expand Down
25 changes: 23 additions & 2 deletions planning/behavior_path_avoidance_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,10 +188,25 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st
return msg;
}

MarkerArray createOverhangLaneletMarkerArray(const ObjectDataArray & objects, std::string && ns)
{
MarkerArray msg;
msg.markers.reserve(objects.size());

for (const auto & object : objects) {
appendMarkerArray(
marker_utils::createLaneletsAreaMarkerArray(
{object.overhang_lanelet}, std::string(ns), 0.0, 0.0, 1.0),
&msg);
}

return msg;
}

MarkerArray avoidableObjectsMarkerArray(const ObjectDataArray & objects, std::string && ns)
{
MarkerArray msg;
msg.markers.reserve(objects.size() * 4);
msg.markers.reserve(objects.size() * 5);

appendMarkerArray(
createObjectsCubeMarkerArray(
Expand All @@ -202,14 +217,15 @@ MarkerArray avoidableObjectsMarkerArray(const ObjectDataArray & objects, std::st
appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg);
appendMarkerArray(createObjectPolygonMarkerArray(objects, ns + "_envelope_polygon"), &msg);
appendMarkerArray(createToDrivableBoundDistance(objects, ns + "_to_drivable_bound"), &msg);
appendMarkerArray(createOverhangLaneletMarkerArray(objects, ns + "_overhang_lanelet"), &msg);

return msg;
}

MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std::string && ns)
{
MarkerArray msg;
msg.markers.reserve(objects.size() * 4);
msg.markers.reserve(objects.size() * 5);

appendMarkerArray(
createObjectsCubeMarkerArray(
Expand All @@ -220,6 +236,7 @@ MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std::
appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg);
appendMarkerArray(createObjectPolygonMarkerArray(objects, ns + "_envelope_polygon"), &msg);
appendMarkerArray(createToDrivableBoundDistance(objects, ns + "_to_drivable_bound"), &msg);
appendMarkerArray(createOverhangLaneletMarkerArray(objects, ns + "_overhang_lanelet"), &msg);

return msg;
}
Expand Down Expand Up @@ -451,6 +468,10 @@ MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const
appendMarkerArray(
createObjectInfoMarkerArray(filtered_objects, "others_" + convertToSnakeCase(ns) + "_info"),
&msg);
appendMarkerArray(
createOverhangLaneletMarkerArray(
filtered_objects, "others_" + convertToSnakeCase(ns) + "_overhang_lanelet"),
&msg);

return msg;
}
Expand Down
29 changes: 11 additions & 18 deletions planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -629,21 +629,16 @@ void AvoidanceModule::fillDebugData(
const auto o_front = data.stop_target_object.value();
const auto object_type = utils::getHighestProbLabel(o_front.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal
? planner_data_->parameters.base_link2front
: 0.0;
const auto constant_distance = helper_->getFrontConstantDistance(o_front);
const auto & vehicle_width = planner_data_->parameters.vehicle_width;

const auto max_avoid_margin = object_parameter.lateral_hard_margin * o_front.distance_factor +
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;

const auto variable = helper_->getSharpAvoidanceDistance(
const auto avoidance_distance = helper_->getSharpAvoidanceDistance(
helper_->getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin));
const auto constant = helper_->getNominalPrepareDistance() +
object_parameter.safety_buffer_longitudinal +
additional_buffer_longitudinal;
const auto total_avoid_distance = variable + constant;
const auto prepare_distance = helper_->getNominalPrepareDistance();
const auto total_avoid_distance = prepare_distance + avoidance_distance + constant_distance;

dead_pose_ = calcLongitudinalOffsetPose(
data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance);
Expand Down Expand Up @@ -1410,16 +1405,14 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const

const auto avoid_margin = object_parameter.lateral_hard_margin * object.distance_factor +
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;
const auto variable = helper_->getMinAvoidanceDistance(
const auto avoidance_distance = helper_->getMinAvoidanceDistance(
helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin));
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal
? planner_data_->parameters.base_link2front
: 0.0;
const auto constant = p->min_prepare_distance + object_parameter.safety_buffer_longitudinal +
additional_buffer_longitudinal + p->stop_buffer;

return object.longitudinal - std::min(variable + constant, p->stop_max_distance);
const auto constant_distance = helper_->getFrontConstantDistance(object);

return object.longitudinal -
std::min(
avoidance_distance + constant_distance + p->min_prepare_distance + p->stop_buffer,
p->stop_max_distance);
}

void AvoidanceModule::insertReturnDeadLine(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,6 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
{
// To be consistent with changes in the ego position, the current shift length is considered.
const auto current_ego_shift = helper_->getEgoShift();
const auto & base_link2rear = data_->parameters.base_link2rear;

// Calculate feasible shift length
const auto get_shift_profile =
Expand All @@ -140,13 +139,10 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(

// calculate remaining distance.
const auto prepare_distance = helper_->getNominalPrepareDistance();
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
: 0.0;
const auto constant = object_parameter.safety_buffer_longitudinal +
additional_buffer_longitudinal + prepare_distance;
const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance;
const auto remaining_distance = object.longitudinal - constant;
const auto constant_distance = helper_->getFrontConstantDistance(object);
const auto has_enough_distance =
object.longitudinal > constant_distance + prepare_distance + nominal_avoid_distance;
const auto remaining_distance = object.longitudinal - constant_distance - prepare_distance;
const auto avoidance_distance =
has_enough_distance ? nominal_avoid_distance : remaining_distance;

Expand Down Expand Up @@ -278,11 +274,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
}
}

// use each object param
const auto object_type = utils::getHighestProbLabel(o.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
// calculate feasible shift length based on behavior policy
const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length);

if (!feasible_shift_profile.has_value()) {
if (o.avoid_required && is_forward_object(o)) {
break;
Expand All @@ -297,12 +290,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(

AvoidLine al_avoid;
{
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
: 0.0;
const auto offset =
object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal;
const auto to_shift_end = o.longitudinal - offset;
const auto constant_distance = helper_->getFrontConstantDistance(o);
const auto to_shift_end = o.longitudinal - constant_distance;
const auto path_front_to_ego = data.arclength_from_ego.at(data.ego_closest_path_index);

// start point (use previous linear shift length as start shift length.)
Expand Down Expand Up @@ -338,8 +327,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(

AvoidLine al_return;
{
const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length;
const auto to_shift_start = o.longitudinal + offset;
const auto constant_distance = helper_->getRearConstantDistance(o);
const auto to_shift_start = o.longitudinal + constant_distance;

// start point
al_return.start_shift_length = feasible_shift_profile.value().first;
Expand Down
39 changes: 23 additions & 16 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -445,6 +445,14 @@ bool isWithinIntersection(
object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon())));
}

bool isOnEgoLane(const ObjectData & object)
{
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
return boost::geometry::within(
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
object.overhang_lanelet.polygon2d().basicPolygon());
}

bool isParallelToEgoLane(const ObjectData & object, const double threshold)
{
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
Expand Down Expand Up @@ -492,6 +500,10 @@ bool isParkedVehicle(
using lanelet::utils::to2D;
using lanelet::utils::conversion::toLaneletPoint;

if (object.is_within_intersection) {
return false;
}

const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
const auto centerline_pos =
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pos).position;
Expand Down Expand Up @@ -566,15 +578,11 @@ bool isParkedVehicle(
return is_left_side_parked_vehicle || is_right_side_parked_vehicle;
}

bool isForceAvoidanceTarget(
bool isAmbiguousStoppedVehicle(
ObjectData & object, const AvoidancePlanningData & data,
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
if (!parameters->enable_force_avoidance_for_stopped_vehicle) {
return false;
}

const auto stop_time_longer_than_threshold =
object.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle;

Expand Down Expand Up @@ -605,6 +613,10 @@ bool isForceAvoidanceTarget(
return false;
}

if (!object.is_on_ego_lane) {
return true;
}

const auto & ego_pose = planner_data->self_odometry->pose.pose;

// force avoidance for stopped vehicle
Expand Down Expand Up @@ -731,24 +743,17 @@ bool isSatisfiedWithVehicleCondition(
const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
using boost::geometry::within;
using lanelet::utils::to2D;
using lanelet::utils::conversion::toLaneletPoint;

object.behavior = getObjectBehavior(object, parameters);
object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler);
object.is_on_ego_lane = isOnEgoLane(object);
object.is_ambiguous = isAmbiguousStoppedVehicle(object, data, planner_data, parameters);

// from here condition check for vehicle type objects.
if (isForceAvoidanceTarget(object, data, planner_data, parameters)) {
if (object.is_ambiguous && parameters->enable_force_avoidance_for_stopped_vehicle) {
return true;
}

// check vehicle shift ratio
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
const auto on_ego_driving_lane = within(
to2D(toLaneletPoint(object_pos)).basicPoint(),
object.overhang_lanelet.polygon2d().basicPolygon());
if (on_ego_driving_lane) {
if (object.is_on_ego_lane) {
if (object.is_parked) {
return true;
} else {
Expand Down Expand Up @@ -1708,6 +1713,8 @@ void filterTargetObjects(
}

if (filtering_utils::isVehicleTypeObject(o)) {
o.is_within_intersection =
filtering_utils::isWithinIntersection(o, planner_data->route_handler);
o.is_parked = filtering_utils::isParkedVehicle(o, planner_data->route_handler, parameters);
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);

Expand Down

0 comments on commit 320bb77

Please sign in to comment.