Skip to content

Commit 1cbdfa3

Browse files
authored
feat(dynamic_obstacle_stop): add option to ignore unavoidable collisions (autowarefoundation#6594)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 1ca97cf commit 1cbdfa3

File tree

6 files changed

+63
-26
lines changed

6 files changed

+63
-26
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/README.md

+13-9
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,11 @@ An object is considered by the module only if it meets all of the following cond
3838
- it is a vehicle (pedestrians are ignored);
3939
- it is moving at a velocity higher than defined by the `minimum_object_velocity` parameter;
4040
- it is not too close to the current position of the ego vehicle;
41+
- it is not unavoidable (only if parameter `ignore_unavoidable_collisions` is set to `true`);
4142
- it is close to the ego path.
4243

44+
An object is considered unavoidable if it is heading towards the ego vehicle such that even if ego stops, a collision would still occur (assuming the object keeps driving in a straight line).
45+
4346
For the last condition,
4447
the object is considered close enough if its lateral distance from the ego path is less than the threshold parameter `minimum_object_distance_from_ego_path` plus half the width of ego and of the object (including the `extra_object_width` parameter).
4548
In addition, the value of the `hysteresis` parameter is added to the minimum distance if a stop point was inserted in the previous iteration.
@@ -74,12 +77,13 @@ the stop point arc length is calculated to be the arc length of the previously f
7477

7578
### Module Parameters
7679

77-
| Parameter | Type | Description |
78-
| --------------------------------------- | ------ | ------------------------------------------------------------------------------------------ |
79-
| `extra_object_width` | double | [m] extra width around detected objects |
80-
| `minimum_object_velocity` | double | [m/s] objects with a velocity bellow this value are ignored |
81-
| `stop_distance_buffer` | double | [m] extra distance to add between the stop point and the collision point |
82-
| `time_horizon` | double | [s] time horizon used for collision checks |
83-
| `hysteresis` | double | [m] once a collision has been detected, this hysteresis is used on the collision detection |
84-
| `decision_duration_buffer` | double | [s] duration between no collision being detected and the stop decision being cancelled |
85-
| `minimum_object_distance_from_ego_path` | double | [m] minimum distance between the footprints of ego and an object to consider for collision |
80+
| Parameter | Type | Description |
81+
| --------------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------ |
82+
| `extra_object_width` | double | [m] extra width around detected objects |
83+
| `minimum_object_velocity` | double | [m/s] objects with a velocity bellow this value are ignored |
84+
| `stop_distance_buffer` | double | [m] extra distance to add between the stop point and the collision point |
85+
| `time_horizon` | double | [s] time horizon used for collision checks |
86+
| `hysteresis` | double | [m] once a collision has been detected, this hysteresis is used on the collision detection |
87+
| `decision_duration_buffer` | double | [s] duration between no collision being detected and the stop decision being cancelled |
88+
| `minimum_object_distance_from_ego_path` | double | [m] minimum distance between the footprints of ego and an object to consider for collision |
89+
| `ignore_unavoidable_collisions` | bool | [-] if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight) |

planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -8,3 +8,4 @@
88
hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection
99
decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled
1010
minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision
11+
ignore_unavoidable_collisions : true # if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight)

planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node
3939
getOrDeclareParameter<double>(node, ns + ".decision_duration_buffer");
4040
pp.minimum_object_distance_from_ego_path =
4141
getOrDeclareParameter<double>(node, ns + ".minimum_object_distance_from_ego_path");
42+
pp.ignore_unavoidable_collisions =
43+
getOrDeclareParameter<bool>(node, ns + ".ignore_unavoidable_collisions");
4244

4345
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
4446
pp.ego_lateral_offset =

planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp

+29-5
Original file line numberDiff line numberDiff line change
@@ -59,13 +59,37 @@ std::vector<autoware_auto_perception_msgs::msg::PredictedObject> filter_predicte
5959
return obj_arc_length > ego_data.longitudinal_offset_to_first_path_idx +
6060
params.ego_longitudinal_offset + o.shape.dimensions.x / 2.0;
6161
};
62-
for (const auto & object : objects.objects)
62+
const auto is_unavoidable = [&](const auto & o) {
63+
const auto & o_pose = o.kinematics.initial_pose_with_covariance.pose;
64+
const auto o_yaw = tf2::getYaw(o_pose.orientation);
65+
const auto ego_yaw = tf2::getYaw(ego_data.pose.orientation);
66+
const auto yaw_diff = std::abs(tier4_autoware_utils::normalizeRadian(o_yaw - ego_yaw));
67+
const auto opposite_heading = yaw_diff > M_PI_2 + M_PI_4;
68+
const auto collision_distance_threshold =
69+
params.ego_lateral_offset + o.shape.dimensions.y / 2.0 + params.hysteresis;
70+
// https://en.wikipedia.org/wiki/Distance_from_a_point_to_a_line#Line_defined_by_point_and_angle
71+
const auto lat_distance = std::abs(
72+
(o_pose.position.y - ego_data.pose.position.y) * std::cos(o_yaw) -
73+
(o_pose.position.x - ego_data.pose.position.x) * std::sin(o_yaw));
74+
auto has_collision = lat_distance <= collision_distance_threshold;
75+
if (ego_data.earliest_stop_pose) {
76+
const auto collision_at_earliest_stop_pose =
77+
std::abs(
78+
(o_pose.position.y - ego_data.earliest_stop_pose->position.y) * std::cos(o_yaw) -
79+
(o_pose.position.x - ego_data.earliest_stop_pose->position.x) * std::sin(o_yaw)) <=
80+
collision_distance_threshold;
81+
has_collision |= collision_at_earliest_stop_pose;
82+
}
83+
return opposite_heading && has_collision;
84+
};
85+
for (const auto & object : objects.objects) {
86+
const auto is_not_too_slow = object.kinematics.initial_twist_with_covariance.twist.linear.x >=
87+
params.minimum_object_velocity;
6388
if (
64-
is_vehicle(object) &&
65-
object.kinematics.initial_twist_with_covariance.twist.linear.x >=
66-
params.minimum_object_velocity &&
67-
is_in_range(object) && is_not_too_close(object))
89+
is_vehicle(object) && is_not_too_slow && is_in_range(object) && is_not_too_close(object) &&
90+
(!params.ignore_unavoidable_collisions || !is_unavoidable(object)))
6891
filtered_objects.push_back(object);
92+
}
6993
return filtered_objects;
7094
}
7195
} // namespace behavior_velocity_planner::dynamic_obstacle_stop

planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp

+16-12
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,9 @@ DynamicObstacleStopModule::DynamicObstacleStopModule(
4444
const rclcpp::Clock::SharedPtr clock)
4545
: SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param))
4646
{
47-
prev_stop_decision_time_ = rclcpp::Time(int64_t{0}, clock->get_clock_type());
47+
prev_stop_decision_time_ =
48+
clock->now() -
49+
rclcpp::Duration(std::chrono::duration<double>(params_.decision_duration_buffer));
4850
velocity_factor_.init(PlanningBehavior::UNKNOWN);
4951
}
5052

@@ -65,10 +67,20 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
6567
motion_utils::findNearestSegmentIndex(ego_data.path.points, ego_data.pose.position);
6668
ego_data.longitudinal_offset_to_first_path_idx = motion_utils::calcLongitudinalOffsetToSegment(
6769
ego_data.path.points, ego_data.first_path_idx, ego_data.pose.position);
70+
const auto min_stop_distance =
71+
motion_utils::calcDecelDistWithJerkAndAccConstraints(
72+
planner_data_->current_velocity->twist.linear.x, 0.0,
73+
planner_data_->current_acceleration->accel.accel.linear.x,
74+
planner_data_->max_stop_acceleration_threshold, -planner_data_->max_stop_jerk_threshold,
75+
planner_data_->max_stop_jerk_threshold)
76+
.value_or(0.0);
77+
ego_data.earliest_stop_pose = motion_utils::calcLongitudinalOffsetPose(
78+
ego_data.path.points, ego_data.pose.position, min_stop_distance);
6879

6980
make_ego_footprint_rtree(ego_data, params_);
81+
const auto start_time = clock_->now();
7082
const auto has_decided_to_stop =
71-
(clock_->now() - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer;
83+
(start_time - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer;
7284
if (!has_decided_to_stop) current_stop_pose_.reset();
7385
double hysteresis = has_decided_to_stop ? params_.hysteresis : 0.0;
7486
const auto dynamic_obstacles =
@@ -80,13 +92,6 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
8092
const auto obstacle_forward_footprints =
8193
make_forward_footprints(dynamic_obstacles, params_, hysteresis);
8294
const auto footprints_duration_us = stopwatch.toc("footprints");
83-
const auto min_stop_distance =
84-
motion_utils::calcDecelDistWithJerkAndAccConstraints(
85-
planner_data_->current_velocity->twist.linear.x, 0.0,
86-
planner_data_->current_acceleration->accel.accel.linear.x,
87-
planner_data_->max_stop_acceleration_threshold, -planner_data_->max_stop_jerk_threshold,
88-
planner_data_->max_stop_jerk_threshold)
89-
.value_or(0.0);
9095
stopwatch.tic("collisions");
9196
const auto collision =
9297
find_earliest_collision(ego_data, dynamic_obstacles, obstacle_forward_footprints, debug_data_);
@@ -101,14 +106,13 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
101106
? motion_utils::calcLongitudinalOffsetPose(
102107
ego_data.path.points, *collision,
103108
-params_.stop_distance_buffer - params_.ego_longitudinal_offset)
104-
: motion_utils::calcLongitudinalOffsetPose(
105-
ego_data.path.points, ego_data.pose.position, min_stop_distance);
109+
: ego_data.earliest_stop_pose;
106110
if (stop_pose) {
107111
const auto use_new_stop_pose = !has_decided_to_stop || motion_utils::calcSignedArcLength(
108112
path->points, stop_pose->position,
109113
current_stop_pose_->position) > 0.0;
110114
if (use_new_stop_pose) current_stop_pose_ = *stop_pose;
111-
prev_stop_decision_time_ = clock_->now();
115+
prev_stop_decision_time_ = start_time;
112116
}
113117
}
114118

planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ struct PlannerParam
4444
double ego_longitudinal_offset;
4545
double ego_lateral_offset;
4646
double minimum_object_distance_from_ego_path;
47+
bool ignore_unavoidable_collisions;
4748
};
4849

4950
struct EgoData
@@ -54,6 +55,7 @@ struct EgoData
5455
geometry_msgs::msg::Pose pose;
5556
tier4_autoware_utils::MultiPolygon2d path_footprints;
5657
Rtree rtree;
58+
std::optional<geometry_msgs::msg::Pose> earliest_stop_pose;
5759
};
5860

5961
/// @brief debug data

0 commit comments

Comments
 (0)