37
37
#include < string>
38
38
#include < tuple>
39
39
#include < unordered_map>
40
+ #include < utility>
40
41
#include < vector>
41
42
42
43
namespace autoware ::motion_planning
@@ -79,24 +80,29 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
79
80
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
80
81
const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
81
82
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 ;
82
88
std::optional<StopObstacle> createStopObstacleForPointCloud (
83
89
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
84
90
const double precise_lateral_dist) const ;
91
+ bool isInsideStopObstacle (const uint8_t label) const ;
92
+ bool isOutsideStopObstacle (const uint8_t label) const ;
85
93
bool isStopObstacle (const uint8_t label) const ;
86
94
bool isInsideCruiseObstacle (const uint8_t label) const ;
87
95
bool isOutsideCruiseObstacle (const uint8_t label) const ;
88
96
bool isCruiseObstacle (const uint8_t label) const ;
89
97
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 ;
93
98
std::optional<CruiseObstacle> createYieldCruiseObstacle (
94
99
const Obstacle & obstacle, const std::vector<TrajectoryPoint> & traj_points);
95
100
std::optional<std::vector<CruiseObstacle>> findYieldCruiseObstacles (
96
101
const std::vector<Obstacle> & obstacles, const std::vector<TrajectoryPoint> & traj_points);
97
102
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);
100
106
std::optional<std::vector<PointWithStamp>> createCollisionPointsForInsideCruiseObstacle (
101
107
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
102
108
const Obstacle & obstacle) const ;
@@ -129,7 +135,9 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
129
135
bool isFrontCollideObstacle (
130
136
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
131
137
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 ;
133
141
bool enable_debug_info_;
134
142
bool enable_calculation_time_info_;
135
143
bool use_pointcloud_for_stop_;
@@ -140,7 +148,8 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
140
148
double min_safe_distance_margin_on_curve_;
141
149
bool suppress_sudden_obstacle_stop_;
142
150
143
- std::vector<int > stop_obstacle_types_;
151
+ std::vector<int > inside_stop_obstacle_types_;
152
+ std::vector<int > outside_stop_obstacle_types_;
144
153
std::vector<int > inside_cruise_obstacle_types_;
145
154
std::vector<int > outside_cruise_obstacle_types_;
146
155
std::vector<int > slow_down_obstacle_types_;
@@ -226,11 +235,20 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
226
235
double ego_obstacle_overlap_time_threshold;
227
236
double max_prediction_time_for_collision_check;
228
237
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;
229
242
// obstacle hold
230
243
double stop_obstacle_hold_time_threshold;
244
+ // reach collision point
245
+ double min_velocity_to_reach_collision_point;
231
246
// prediction resampling
232
247
double prediction_resampling_time_interval;
233
248
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;
234
252
// max lateral margin
235
253
double max_lat_margin_for_stop;
236
254
double max_lat_margin_for_stop_against_unknown;
0 commit comments