Skip to content

Commit

Permalink
feat(dynamic_avoidance): avoid pedestrians (#6553)
Browse files Browse the repository at this point in the history
new feature: avoid against the pedestrians
Signed-off-by: Yuki Takagi <[email protected]>
  • Loading branch information
yuki-takagi-66 authored Apr 19, 2024
1 parent e11b1f4 commit e5b3f60
Show file tree
Hide file tree
Showing 7 changed files with 547 additions and 56 deletions.
30 changes: 25 additions & 5 deletions planning/behavior_path_dynamic_avoidance_module/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ Obstacle Avoidance module modifies the path to be followed so that it fits withi
Avoidance functions are also provided by the [Avoidance module](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_avoidance_module/), but these modules have different roles.
The Avoidance module performs avoidance through the outside of own lanes but cannot avoid the moving objects.
On the other hand, this module can avoid moving objects.
For this reason, the word "dynamic" is used in the modules's name.
For this reason, the word "dynamic" is used in the module's name.
The table below lists the avoidance modules that can handle each situation.

| | avoid within the own lane | avoid through the outside of own lanes |
Expand All @@ -23,7 +23,7 @@ The table below lists the avoidance modules that can handle each situation.
## Policy of algorithms

Here, we describe the policy of inner algorithms.
The inner algorithms can be separated into two parts: The first decide whether to avoid the obstacles and the second cuts off the drivable area against the corresponding obstacle.
The inner algorithms can be separated into two parts: The first decides whether to avoid the obstacles and the second cuts off the drivable area against the corresponding obstacle.

### Select obstacles to avoid

Expand All @@ -36,7 +36,7 @@ The other, _can be avoided_ denotes whether it can be avoided without risk to th
For this purpose, the module judges whether the obstacle can be avoided with satisfying the constraints of lateral acceleration and lateral jerk.
For example, the module decides not to avoid an object that is too close or fast in the lateral direction.

### Cuts off the drivable area against the selected obstacles
### Cuts off the drivable area against the selected vehicles

For the selected obstacles to be avoided, the module cuts off the drivable area.
As inputs to decide the shapes of cut-off polygons, poses of the obstacles are mainly used, assuming they move in parallel to the ego's path, instead of its predicted path.
Expand All @@ -45,7 +45,7 @@ Furthermore, the output drivable area shape is designed as a rectangular cutout

#### Determination of lateral dimension

Lateral dimensions of the polygon is calculated as follows.
The lateral dimensions of the polygon are calculated as follows.
The polygon's width to extract from the drivable area is the obstacle width and `drivable_area_generation.lat_offset_from_obstacle`.
We can limit the lateral shift length by `drivable_area_generation.max_lat_offset_to_avoid`.

Expand All @@ -55,14 +55,34 @@ We can limit the lateral shift length by `drivable_area_generation.max_lat_offse

Then, extracting the same directional and opposite directional obstacles from the drivable area will work as follows considering TTC (time to collision).

Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g. The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.).
Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g., The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.).

Same directional obstacles (Parameter names may differ from implementation)
![same_directional_object](./image/same_directional_object.svg)

Opposite directional obstacles (Parameter names may differ from implementation)
![opposite_directional_object](./image/opposite_directional_object.svg)

### Cuts off the drivable area against the selected pedestrians

Then, we describe the logic to generate the drivable areas against pedestrians to be avoided.
Objects of this type are considered to have priority right of way over the ego's vehicle while ensuring a minimum safety of the ego's vehicle.
In other words, the module assigns a drivable area to an obstacle with a specific margin based on the predicted paths with specific confidences for a specific time interval, as shown in the following figure.

<figure>
<img src="./image/2024-04-18_15-13-01.png" width="600">
<figcaption> Restriction areas are generated from each pedestrian's predicted paths</figcaption>
</figure>

Apart from polygons for objects, the module also generates another polygon to ensure the ego's safety, i.e., to avoid abrupt steering or significant changes from the path.
This is similar to avoidance against the vehicles and takes precedence over keeping a safe distance from the object to be avoided.
As a result, as shown in the figure below, the polygons around the objects reduced by the secured polygon of the ego are subtracted from the ego's drivable area.

<figure>
<img src="./image/2024-04-18_15-32-03.png" width="600">
<figcaption> Ego's minimum requirements are prioritized against object margin</figcaption>
</figure>

## Example

<figure>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
bus: true
trailer: true
unknown: false
bicycle: false
bicycle: true
motorcycle: true
pedestrian: false
pedestrian: true

max_obstacle_vel: 100.0 # [m/s]
min_obstacle_vel: 0.0 # [m/s]
Expand All @@ -38,8 +38,9 @@
crossing_object:
min_overtaking_object_vel: 1.0
max_overtaking_object_angle: 1.05
min_oncoming_object_vel: 0.0
min_oncoming_object_vel: 1.0
max_oncoming_object_angle: 0.523
max_pedestrian_crossing_vel: 0.8

front_object:
max_object_angle: 0.785
Expand All @@ -54,7 +55,11 @@
object_path_base:
min_longitudinal_polygon_margin: 3.0 # [m]

lat_offset_from_obstacle: 0.8 # [m]
lat_offset_from_obstacle: 1.0 # [m]
margin_distance_around_pedestrian: 2.0 # [m]
predicted_path:
end_time_to_consider: 3.0 # [s]
threshold_confidence: 0.0 # [] not probability
max_lat_offset_to_avoid: 0.5 # [m]
max_time_for_object_lat_shift: 0.0 # [s]
lpf_gain_for_lat_avoid_to_offset: 0.9 # [-]
Expand All @@ -66,12 +71,12 @@
# for same directional object
overtaking_object:
max_time_to_collision: 40.0 # [s]
start_duration_to_avoid: 2.0 # [s]
end_duration_to_avoid: 4.0 # [s]
start_duration_to_avoid: 1.0 # [s]
end_duration_to_avoid: 1.0 # [s]
duration_to_hold_avoidance: 3.0 # [s]

# for opposite directional object
oncoming_object:
max_time_to_collision: 40.0 # [s] This value should be the same as overtaking_object's one to suppress chattering of this value for parked vehicles
start_duration_to_avoid: 12.0 # [s]
start_duration_to_avoid: 1.0 # [s]
end_duration_to_avoid: 0.0 # [s]
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_

#include "behavior_path_planner_common/interface/scene_module_interface.hpp"
#include "tier4_autoware_utils/system/stop_watch.hpp"

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
Expand Down Expand Up @@ -54,19 +55,38 @@ std::vector<T> getAllKeys(const std::unordered_map<T, S> & map)
namespace behavior_path_planner
{
using autoware_auto_perception_msgs::msg::PredictedPath;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using tier4_autoware_utils::Polygon2d;

struct MinMaxValue
{
double min_value{0.0};
double max_value{0.0};
MinMaxValue operator+(const double scalar) const
{
MinMaxValue ret;
ret.min_value = min_value + scalar;
ret.max_value = max_value + scalar;
return ret;
};
void swap() { std::swap(min_value, max_value); }
};

enum class PolygonGenerationMethod {
EGO_PATH_BASE = 0,
OBJECT_PATH_BASE,
};

enum class ObjectType {
OUT_OF_SCOPE = 0, // The module do not care about this type of objects.
REGULATED, // The module assumes this type of objects move in parallel against lanes. Drivable
// areas are divided proportionately with the ego. Typically, cars, bus and trucks
// are classified to this type.
UNREGULATED, // The module does not assume the objects move in parallel against lanes and
// assigns drivable area with priority to ego. Typically, pedestrians should be
// classified to this type.
};

struct DynamicAvoidanceParameters
{
// common
Expand Down Expand Up @@ -103,12 +123,18 @@ struct DynamicAvoidanceParameters
double max_overtaking_crossing_object_angle{0.0};
double min_oncoming_crossing_object_vel{0.0};
double max_oncoming_crossing_object_angle{0.0};
double max_pedestrian_crossing_vel{0.0};
double max_stopped_object_vel{0.0};

// drivable area generation
PolygonGenerationMethod polygon_generation_method{};
double min_obj_path_based_lon_polygon_margin{0.0};
double lat_offset_from_obstacle{0.0};
double margin_distance_around_pedestrian{0.0};

double end_time_to_consider{0.0};
double threshold_confidence{0.0};

double max_lat_offset_to_avoid{0.0};
double max_time_for_lat_shift{0.0};
double lpf_gain_for_lat_avoid_to_offset{0.0};
Expand Down Expand Up @@ -148,6 +174,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
const bool arg_is_object_on_ego_path,
const std::optional<rclcpp::Time> & arg_latest_time_inside_ego_path)
: uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)),
label(predicted_object.classification.front().label),
pose(predicted_object.kinematics.initial_pose_with_covariance.pose),
shape(predicted_object.shape),
vel(arg_vel),
Expand All @@ -161,6 +188,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
}

std::string uuid{};
uint8_t label{};
geometry_msgs::msg::Pose pose{};
autoware_auto_perception_msgs::msg::Shape shape;
double vel{0.0};
Expand All @@ -178,6 +206,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
std::vector<PathPointWithLaneId> ref_path_points_for_obj_poly;
LatFeasiblePaths ego_lat_feasible_paths;

// add additional information (not update to the latest data)
void update(
const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid,
const bool arg_is_collision_left, const bool arg_should_be_avoided,
Expand Down Expand Up @@ -216,7 +245,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface

// increase counter
if (counter_map_.count(uuid) != 0) {
counter_map_.at(uuid) = std::min(max_count_ + 1, std::max(1, counter_map_.at(uuid) + 1));
counter_map_.at(uuid) = std::min(max_count_, std::max(1, counter_map_.at(uuid) + 1));
} else {
counter_map_.emplace(uuid, 1);
}
Expand All @@ -236,7 +265,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
}
for (const auto & uuid : not_updated_uuids) {
if (counter_map_.count(uuid) != 0) {
counter_map_.at(uuid) = std::max(min_count_ - 1, std::min(-1, counter_map_.at(uuid) - 1));
counter_map_.at(uuid) = std::max(0, counter_map_.at(uuid) - 1);
} else {
counter_map_.emplace(uuid, -1);
}
Expand All @@ -253,7 +282,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
std::remove_if(
valid_object_uuids_.begin(), valid_object_uuids_.end(),
[&](const auto & uuid) {
return counter_map_.count(uuid) == 0 || counter_map_.at(uuid) < max_count_;
return counter_map_.count(uuid) == 0 || counter_map_.at(uuid) < min_count_;
}),
valid_object_uuids_.end());

Expand Down Expand Up @@ -340,13 +369,23 @@ class DynamicAvoidanceModule : public SceneModuleInterface
const double max_lon_offset;
const double min_lon_offset;
};
struct EgoPathReservePoly
{
const tier4_autoware_utils::Polygon2d left_avoid;
const tier4_autoware_utils::Polygon2d right_avoid;
};

bool canTransitSuccessState() override;

bool canTransitFailureState() override { return false; }

bool isLabelTargetObstacle(const uint8_t label) const;
void updateTargetObjects();
ObjectType getObjectType(const uint8_t label) const;
void registerRegulatedObjects(const std::vector<DynamicAvoidanceObject> & prev_objects);
void registerUnregulatedObjects(const std::vector<DynamicAvoidanceObject> & prev_objects);
void determineWhetherToAvoidAgainstRegulatedObjects(
const std::vector<DynamicAvoidanceObject> & prev_objects);
void determineWhetherToAvoidAgainstUnregulatedObjects(
const std::vector<DynamicAvoidanceObject> & prev_objects);
LatFeasiblePaths generateLateralFeasiblePaths(
const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const;
void updateRefPathBeforeLaneChange(const std::vector<PathPointWithLaneId> & ego_ref_path_points);
Expand Down Expand Up @@ -378,18 +417,24 @@ class DynamicAvoidanceModule : public SceneModuleInterface
const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel,
const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape,
const TimeWhileCollision & time_while_collision) const;
std::optional<MinMaxValue> calcMinMaxLateralOffsetToAvoid(
std::optional<MinMaxValue> calcMinMaxLateralOffsetToAvoidRegulatedObject(
const std::vector<PathPointWithLaneId> & ref_path_points_for_obj_poly,
const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel,
const bool is_collision_left, const double obj_normal_vel,
const std::optional<DynamicAvoidanceObject> & prev_object) const;

std::optional<MinMaxValue> calcMinMaxLateralOffsetToAvoidUnregulatedObject(
const std::vector<PathPointWithLaneId> & ref_path_points_for_obj_poly,
const std::optional<DynamicAvoidanceObject> & prev_object,
const DynamicAvoidanceObject & object) const;
std::pair<lanelet::ConstLanelets, lanelet::ConstLanelets> getAdjacentLanes(
const double forward_distance, const double backward_distance) const;
std::optional<tier4_autoware_utils::Polygon2d> calcEgoPathBasedDynamicObstaclePolygon(
const DynamicAvoidanceObject & object) const;
std::optional<tier4_autoware_utils::Polygon2d> calcObjectPathBasedDynamicObstaclePolygon(
const DynamicAvoidanceObject & object) const;
std::optional<tier4_autoware_utils::Polygon2d> calcPredictedPathBasedDynamicObstaclePolygon(
const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const;
EgoPathReservePoly calcEgoPathReservePoly(const PathWithLaneId & ego_path) const;

void printIgnoreReason(const std::string & obj_uuid, const std::string & reason)
{
Expand All @@ -406,6 +451,10 @@ class DynamicAvoidanceModule : public SceneModuleInterface
std::shared_ptr<DynamicAvoidanceParameters> parameters_;

TargetObjectsManager target_objects_manager_;

mutable tier4_autoware_utils::StopWatch<
std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock>
stop_watch_;
};
} // namespace behavior_path_planner

Expand Down
17 changes: 17 additions & 0 deletions planning/behavior_path_dynamic_avoidance_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node)
node->declare_parameter<double>(ns + "crossing_object.min_oncoming_object_vel");
p.max_oncoming_crossing_object_angle =
node->declare_parameter<double>(ns + "crossing_object.max_oncoming_object_angle");
p.max_pedestrian_crossing_vel =
node->declare_parameter<double>(ns + "crossing_object.max_pedestrian_crossing_vel");

p.max_stopped_object_vel =
node->declare_parameter<double>(ns + "stopped_object.max_object_vel");
Expand All @@ -111,6 +113,12 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node)
p.min_obj_path_based_lon_polygon_margin =
node->declare_parameter<double>(ns + "object_path_base.min_longitudinal_polygon_margin");
p.lat_offset_from_obstacle = node->declare_parameter<double>(ns + "lat_offset_from_obstacle");
p.margin_distance_around_pedestrian =
node->declare_parameter<double>(ns + "margin_distance_around_pedestrian");
p.end_time_to_consider =
node->declare_parameter<double>(ns + "predicted_path.end_time_to_consider");
p.threshold_confidence =
node->declare_parameter<double>(ns + "predicted_path.threshold_confidence");
p.max_lat_offset_to_avoid = node->declare_parameter<double>(ns + "max_lat_offset_to_avoid");
p.max_time_for_lat_shift =
node->declare_parameter<double>(ns + "max_time_for_object_lat_shift");
Expand Down Expand Up @@ -214,6 +222,9 @@ void DynamicAvoidanceModuleManager::updateModuleParams(
updateParam<double>(
parameters, ns + "crossing_object.max_oncoming_object_angle",
p->max_oncoming_crossing_object_angle);
updateParam<double>(
parameters, ns + "crossing_object.max_pedestrian_crossing_vel",
p->max_pedestrian_crossing_vel);

updateParam<double>(
parameters, ns + "stopped_object.max_object_vel", p->max_stopped_object_vel);
Expand All @@ -231,6 +242,12 @@ void DynamicAvoidanceModuleManager::updateModuleParams(
parameters, ns + "object_path_base.min_longitudinal_polygon_margin",
p->min_obj_path_based_lon_polygon_margin);
updateParam<double>(parameters, ns + "lat_offset_from_obstacle", p->lat_offset_from_obstacle);
updateParam<double>(
parameters, ns + "margin_distance_around_pedestrian", p->margin_distance_around_pedestrian);
updateParam<double>(
parameters, ns + "predicted_path.end_time_to_consider", p->end_time_to_consider);
updateParam<double>(
parameters, ns + "predicted_path.threshold_confidence", p->threshold_confidence);
updateParam<double>(parameters, ns + "max_lat_offset_to_avoid", p->max_lat_offset_to_avoid);
updateParam<double>(
parameters, ns + "max_time_for_object_lat_shift", p->max_time_for_lat_shift);
Expand Down
Loading

0 comments on commit e5b3f60

Please sign in to comment.