Skip to content

Commit 88e2ae1

Browse files
author
Berkay Karaman
authored
feat(obstacle_cruise_planner): improve stop and cruise behavior for cut-in & out (autowarefoundation#8072)
* feat(obstacle_cruise_planner): improve stop and cruise behavior for cut-in & out Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * cleanup, add stop safety margin for transient objects Signed-off-by: Berkay Karaman <berkay@leodrive.ai> style(pre-commit): autofix * fix: debug Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * fix: precommit error Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * fix: unused-variable Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * feat: improve cruise behavior for outside obstacles Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * fix projected velocity, improve transient obstacle behavior Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * feat: add predefined deceleration rate for VRUs Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * feat: update Signed-off-by: Berkay Karaman <berkay@leodrive.ai> --------- Signed-off-by: Berkay Karaman <berkay@leodrive.ai>
1 parent bd2cea4 commit 88e2ae1

File tree

6 files changed

+502
-153
lines changed

6 files changed

+502
-153
lines changed

planning/autoware_obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml

+27-8
Original file line numberDiff line numberDiff line change
@@ -29,15 +29,26 @@
2929
suppress_sudden_obstacle_stop: false
3030

3131
stop_obstacle_type:
32-
unknown: true
33-
car: true
34-
truck: true
35-
bus: true
36-
trailer: true
37-
motorcycle: true
38-
bicycle: true
39-
pedestrian: true
4032
pointcloud: false
33+
inside:
34+
unknown: true
35+
car: true
36+
truck: true
37+
bus: true
38+
trailer: true
39+
motorcycle: true
40+
bicycle: true
41+
pedestrian: true
42+
43+
outside:
44+
unknown: false
45+
car: true
46+
truck: true
47+
bus: true
48+
trailer: true
49+
motorcycle: true
50+
bicycle: true
51+
pedestrian: true
4152

4253
cruise_obstacle_type:
4354
inside:
@@ -99,6 +110,12 @@
99110
stop:
100111
max_lat_margin: 0.3 # lateral margin between the obstacles except for unknown and ego's footprint
101112
max_lat_margin_against_unknown: 0.3 # lateral margin between the unknown obstacles and ego's footprint
113+
min_velocity_to_reach_collision_point: 2.0 # minimum velocity margin to calculate time to reach collision [m/s]
114+
outside_obstacle:
115+
max_lateral_time_margin: 4.0 # time threshold of lateral margin between the obstacles and ego's footprint [s]
116+
num_of_predicted_paths: 3 # number of the highest confidence predicted path to check collision between obstacle and ego
117+
pedestrian_deceleration_rate: 0.5 # planner perceives pedestrians will stop with this rate to avoid unnecessary stops [m/ss]
118+
bicycle_deceleration_rate: 0.5 # planner perceives bicycles will stop with this rate to avoid unnecessary stops [m/ss]
102119
crossing_obstacle:
103120
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]
104121

@@ -108,6 +125,8 @@
108125
obstacle_velocity_threshold : 3.5 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s]
109126
ego_obstacle_overlap_time_threshold : 2.0 # time threshold to decide cut-in obstacle for cruise or stop [s]
110127
max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego
128+
max_lateral_time_margin: 5.0 # time threshold of lateral margin between obstacle and trajectory band with ego's width [s]
129+
num_of_predicted_paths: 3 # number of the highest confidence predicted path to check collision between obstacle and ego
111130
yield:
112131
enable_yield: true
113132
lat_distance_threshold: 5.0 # lateral margin between obstacle in neighbor lanes and trajectory band with ego's width for yielding

planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -58,10 +58,13 @@ struct Obstacle
5858
Obstacle(
5959
const rclcpp::Time & arg_stamp, const PredictedObject & object,
6060
const geometry_msgs::msg::Pose & arg_pose, const double ego_to_obstacle_distance,
61-
const double lat_dist_from_obstacle_to_traj)
61+
const double lat_dist_from_obstacle_to_traj, const double longitudinal_velocity,
62+
const double approach_velocity)
6263
: stamp(arg_stamp),
6364
ego_to_obstacle_distance(ego_to_obstacle_distance),
6465
lat_dist_from_obstacle_to_traj(lat_dist_from_obstacle_to_traj),
66+
longitudinal_velocity(longitudinal_velocity),
67+
approach_velocity(approach_velocity),
6568
pose(arg_pose),
6669
orientation_reliable(true),
6770
twist(object.kinematics.initial_twist_with_covariance.twist),
@@ -94,6 +97,8 @@ struct Obstacle
9497
rclcpp::Time stamp; // This is not the current stamp, but when the object was observed.
9598
double ego_to_obstacle_distance;
9699
double lat_dist_from_obstacle_to_traj;
100+
double longitudinal_velocity;
101+
double approach_velocity;
97102

98103
// for PredictedObject
99104
geometry_msgs::msg::Pose pose; // interpolated with the current stamp

planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp

+25-7
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
#include <string>
3838
#include <tuple>
3939
#include <unordered_map>
40+
#include <utility>
4041
#include <vector>
4142

4243
namespace autoware::motion_planning
@@ -79,24 +80,29 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
7980
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
8081
const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
8182
const double precise_lateral_dist) const;
83+
std::optional<std::pair<geometry_msgs::msg::Point, double>>
84+
createCollisionPointForOutsideStopObstacle(
85+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
86+
const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
87+
const PredictedPath & resampled_predicted_path, double max_lat_margin_for_stop) const;
8288
std::optional<StopObstacle> createStopObstacleForPointCloud(
8389
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
8490
const double precise_lateral_dist) const;
91+
bool isInsideStopObstacle(const uint8_t label) const;
92+
bool isOutsideStopObstacle(const uint8_t label) const;
8593
bool isStopObstacle(const uint8_t label) const;
8694
bool isInsideCruiseObstacle(const uint8_t label) const;
8795
bool isOutsideCruiseObstacle(const uint8_t label) const;
8896
bool isCruiseObstacle(const uint8_t label) const;
8997
bool isSlowDownObstacle(const uint8_t label) const;
90-
std::optional<geometry_msgs::msg::Point> createCollisionPointForStopObstacle(
91-
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
92-
const Obstacle & obstacle) const;
9398
std::optional<CruiseObstacle> createYieldCruiseObstacle(
9499
const Obstacle & obstacle, const std::vector<TrajectoryPoint> & traj_points);
95100
std::optional<std::vector<CruiseObstacle>> findYieldCruiseObstacles(
96101
const std::vector<Obstacle> & obstacles, const std::vector<TrajectoryPoint> & traj_points);
97102
std::optional<CruiseObstacle> createCruiseObstacle(
98-
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
99-
const Obstacle & obstacle, const double precise_lat_dist);
103+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
104+
const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
105+
const double precise_lat_dist);
100106
std::optional<std::vector<PointWithStamp>> createCollisionPointsForInsideCruiseObstacle(
101107
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
102108
const Obstacle & obstacle) const;
@@ -129,7 +135,9 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
129135
bool isFrontCollideObstacle(
130136
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
131137
const size_t first_collision_idx) const;
132-
138+
double calcTimeToReachCollisionPoint(
139+
const Odometry & odometry, const geometry_msgs::msg::Point & collision_point,
140+
const std::vector<TrajectoryPoint> & traj_points, const double abs_ego_offset) const;
133141
bool enable_debug_info_;
134142
bool enable_calculation_time_info_;
135143
bool use_pointcloud_for_stop_;
@@ -140,7 +148,8 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
140148
double min_safe_distance_margin_on_curve_;
141149
bool suppress_sudden_obstacle_stop_;
142150

143-
std::vector<int> stop_obstacle_types_;
151+
std::vector<int> inside_stop_obstacle_types_;
152+
std::vector<int> outside_stop_obstacle_types_;
144153
std::vector<int> inside_cruise_obstacle_types_;
145154
std::vector<int> outside_cruise_obstacle_types_;
146155
std::vector<int> slow_down_obstacle_types_;
@@ -226,11 +235,20 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
226235
double ego_obstacle_overlap_time_threshold;
227236
double max_prediction_time_for_collision_check;
228237
double crossing_obstacle_traj_angle_threshold;
238+
int num_of_predicted_paths_for_outside_cruise_obstacle;
239+
int num_of_predicted_paths_for_outside_stop_obstacle;
240+
double pedestrian_deceleration_rate;
241+
double bicycle_deceleration_rate;
229242
// obstacle hold
230243
double stop_obstacle_hold_time_threshold;
244+
// reach collision point
245+
double min_velocity_to_reach_collision_point;
231246
// prediction resampling
232247
double prediction_resampling_time_interval;
233248
double prediction_resampling_time_horizon;
249+
// max lateral time margin
250+
double max_lat_time_margin_for_stop;
251+
double max_lat_time_margin_for_cruise;
234252
// max lateral margin
235253
double max_lat_margin_for_stop;
236254
double max_lat_margin_for_stop_against_unknown;

planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/polygon_utils.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,11 @@ std::optional<std::pair<geometry_msgs::msg::Point, double>> getCollisionPoint(
4343
const Obstacle & obstacle, const bool is_driving_forward,
4444
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
4545

46+
std::optional<std::pair<geometry_msgs::msg::Point, double>> getCollisionPoint(
47+
const std::vector<TrajectoryPoint> & traj_points, const size_t collision_idx,
48+
const std::vector<PointWithStamp> & collision_points, const bool is_driving_forward,
49+
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
50+
4651
std::vector<PointWithStamp> getCollisionPoints(
4752
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polygons,
4853
const rclcpp::Time & obstacle_stamp, const PredictedPath & predicted_path, const Shape & shape,

0 commit comments

Comments
 (0)