18
18
#include " autoware/behavior_path_goal_planner_module/decision_state.hpp"
19
19
#include " autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp"
20
20
#include " autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp"
21
- #include " autoware/behavior_path_goal_planner_module/goal_searcher.hpp"
22
21
#include " autoware/behavior_path_goal_planner_module/thread_data.hpp"
23
- #include " autoware/behavior_path_planner_common/interface/scene_module_interface.hpp"
24
22
#include " autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp"
25
23
#include " autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
26
24
@@ -89,27 +87,44 @@ struct PullOverContextData
89
87
PullOverContextData () = delete ;
90
88
explicit PullOverContextData (
91
89
const bool is_stable_safe_path, const PredictedObjects & static_objects,
92
- const PredictedObjects & dynamic_objects, std::optional<PullOverPath> && pull_over_path_opt ,
93
- const std::vector<PullOverPath> & pull_over_path_candidates ,
94
- const PathDecisionState & prev_state )
90
+ const PredictedObjects & dynamic_objects, const PathDecisionState & prev_state ,
91
+ const bool is_stopped, const LaneParkingResponse & lane_parking_response ,
92
+ const FreespaceParkingResponse & freespace_parking_response )
95
93
: is_stable_safe_path(is_stable_safe_path),
96
94
static_target_objects(static_objects),
97
95
dynamic_target_objects(dynamic_objects),
98
- pull_over_path_opt(pull_over_path_opt),
99
- pull_over_path_candidates(pull_over_path_candidates),
100
96
prev_state_for_debug(prev_state),
101
- last_path_idx_increment_time(std::nullopt)
97
+ is_stopped(is_stopped),
98
+ lane_parking_response(lane_parking_response),
99
+ freespace_parking_response(freespace_parking_response)
102
100
{
103
101
}
104
- const bool is_stable_safe_path;
105
- const PredictedObjects static_target_objects;
106
- const PredictedObjects dynamic_target_objects;
107
- // TODO(soblin): due to deceleratePath(), this cannot be const member(velocity is modified by it)
102
+ // TODO(soblin): make following variables private
103
+ bool is_stable_safe_path;
104
+ PredictedObjects static_target_objects;
105
+ PredictedObjects dynamic_target_objects;
106
+ PathDecisionState prev_state_for_debug;
107
+ bool is_stopped;
108
+ LaneParkingResponse lane_parking_response;
109
+ FreespaceParkingResponse freespace_parking_response;
108
110
std::optional<PullOverPath> pull_over_path_opt;
109
- const std::vector<PullOverPath> pull_over_path_candidates;
110
- // TODO(soblin): goal_candidate_from_thread, modifed_goal_pose_from_thread, closest_start_pose
111
- const PathDecisionState prev_state_for_debug;
111
+ std::optional<rclcpp::Time> last_path_update_time;
112
112
std::optional<rclcpp::Time> last_path_idx_increment_time;
113
+
114
+ void update (
115
+ const bool is_stable_safe_path_, const PredictedObjects static_target_objects_,
116
+ const PredictedObjects dynamic_target_objects_, const PathDecisionState prev_state_for_debug_,
117
+ const bool is_stopped_, const LaneParkingResponse & lane_parking_response_,
118
+ const FreespaceParkingResponse & freespace_parking_response_)
119
+ {
120
+ is_stable_safe_path = is_stable_safe_path_;
121
+ static_target_objects = static_target_objects_;
122
+ dynamic_target_objects = dynamic_target_objects_;
123
+ prev_state_for_debug = prev_state_for_debug_;
124
+ is_stopped = is_stopped_;
125
+ lane_parking_response = lane_parking_response_;
126
+ freespace_parking_response = freespace_parking_response_;
127
+ }
113
128
};
114
129
115
130
bool isOnModifiedGoal (
@@ -133,6 +148,11 @@ bool checkOccupancyGridCollision(
133
148
const PathWithLaneId & path,
134
149
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map);
135
150
151
+ // freespace parking
152
+ std::optional<PullOverPath> planFreespacePath (
153
+ const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects,
154
+ std::shared_ptr<PullOverPlannerBase> freespace_planner);
155
+
136
156
bool isStopped (
137
157
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> & odometry_buffer,
138
158
const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower,
@@ -150,6 +170,61 @@ class ScopedFlag
150
170
std::atomic<bool > & flag_;
151
171
};
152
172
173
+ class LaneParkingPlanner
174
+ {
175
+ public:
176
+ LaneParkingPlanner (
177
+ rclcpp::Node & node, std::mutex & lane_parking_mutex,
178
+ const std::optional<LaneParkingRequest> & request, LaneParkingResponse & response,
179
+ std::atomic<bool > & is_lane_parking_cb_running, const rclcpp::Logger & logger,
180
+ const GoalPlannerParameters & parameters);
181
+ rclcpp::Logger getLogger () const { return logger_; }
182
+ void onTimer ();
183
+
184
+ private:
185
+ std::mutex & mutex_;
186
+ const std::optional<LaneParkingRequest> & request_;
187
+ LaneParkingResponse & response_;
188
+ std::atomic<bool > & is_lane_parking_cb_running_;
189
+ rclcpp::Logger logger_;
190
+
191
+ std::vector<std::shared_ptr<PullOverPlannerBase>> pull_over_planners_;
192
+ };
193
+
194
+ class FreespaceParkingPlanner
195
+ {
196
+ public:
197
+ FreespaceParkingPlanner (
198
+ std::mutex & freespace_parking_mutex, const std::optional<FreespaceParkingRequest> & request,
199
+ FreespaceParkingResponse & response, std::atomic<bool > & is_freespace_parking_cb_running,
200
+ const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock,
201
+ const std::shared_ptr<PullOverPlannerBase> freespace_planner)
202
+ : mutex_(freespace_parking_mutex),
203
+ request_ (request),
204
+ response_(response),
205
+ is_freespace_parking_cb_running_(is_freespace_parking_cb_running),
206
+ logger_(logger),
207
+ clock_(clock),
208
+ freespace_planner_(freespace_planner)
209
+ {
210
+ }
211
+ void onTimer ();
212
+
213
+ private:
214
+ std::mutex & mutex_;
215
+ const std::optional<FreespaceParkingRequest> & request_;
216
+ FreespaceParkingResponse & response_;
217
+ std::atomic<bool > & is_freespace_parking_cb_running_;
218
+ rclcpp::Logger logger_;
219
+ rclcpp::Clock::SharedPtr clock_;
220
+
221
+ std::shared_ptr<PullOverPlannerBase> freespace_planner_;
222
+
223
+ bool isStuck (
224
+ const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
225
+ const FreespaceParkingRequest & req) const ;
226
+ };
227
+
153
228
class GoalPlannerModule : public SceneModuleInterface
154
229
{
155
230
public:
@@ -217,48 +292,16 @@ class GoalPlannerModule : public SceneModuleInterface
217
292
CandidateOutput planCandidate () const override { return CandidateOutput{}; }
218
293
219
294
private:
220
- /* *
221
- * @brief shared data for onTimer(onTimer/onFreespaceParkingTimer just read this)
222
- */
223
- struct GoalPlannerData
224
- {
225
- GoalPlannerData (
226
- const PlannerData & planner_data, const GoalPlannerParameters & parameters,
227
- const BehaviorModuleOutput & previous_module_output_)
228
- {
229
- initializeOccupancyGridMap (planner_data, parameters);
230
- previous_module_output = previous_module_output_;
231
- last_previous_module_output = previous_module_output_;
232
- };
233
- GoalPlannerParameters parameters;
234
- autoware::universe_utils::LinearRing2d vehicle_footprint;
235
-
236
- PlannerData planner_data;
237
- ModuleStatus current_status;
238
- BehaviorModuleOutput previous_module_output;
239
- BehaviorModuleOutput last_previous_module_output; // <! previous "previous_module_output"
240
- GoalCandidates goal_candidates; // <! only the positional information of goal_candidates
241
-
242
- // collision detector
243
- // need to be shared_ptr to be used in planner and goal searcher
244
- std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map;
245
-
246
- const BehaviorModuleOutput & getPreviousModuleOutput () const { return previous_module_output; }
247
- const ModuleStatus & getCurrentStatus () const { return current_status; }
248
- void updateOccupancyGrid ();
249
- GoalPlannerData clone () const ;
250
- void update (
251
- const GoalPlannerParameters & parameters, const PlannerData & planner_data,
252
- const ModuleStatus & current_status, const BehaviorModuleOutput & previous_module_output,
253
- const autoware::universe_utils::LinearRing2d & vehicle_footprint,
254
- const GoalCandidates & goal_candidates);
255
-
256
- private:
257
- void initializeOccupancyGridMap (
258
- const PlannerData & planner_data, const GoalPlannerParameters & parameters);
259
- };
260
- std::optional<GoalPlannerData> gp_planner_data_{std::nullopt};
261
- std::mutex gp_planner_data_mutex_;
295
+ std::pair<LaneParkingResponse, FreespaceParkingResponse> syncWithThreads ();
296
+
297
+ // NOTE: never access to following variables except in updateData()!!!
298
+ std::mutex lane_parking_mutex_;
299
+ std::optional<LaneParkingRequest> lane_parking_request_;
300
+ LaneParkingResponse lane_parking_response_;
301
+
302
+ std::mutex freespace_parking_mutex_;
303
+ std::optional<FreespaceParkingRequest> freespace_parking_request_;
304
+ FreespaceParkingResponse freespace_parking_response_;
262
305
263
306
/*
264
307
* state transitions and plan function used in each state
@@ -297,9 +340,6 @@ class GoalPlannerModule : public SceneModuleInterface
297
340
298
341
autoware::vehicle_info_utils::VehicleInfo vehicle_info_{};
299
342
300
- // planner
301
- std::vector<std::shared_ptr<PullOverPlannerBase>> pull_over_planners_;
302
- std::unique_ptr<PullOverPlannerBase> freespace_planner_;
303
343
std::unique_ptr<FixedGoalPlannerBase> fixed_goal_planner_;
304
344
305
345
// goal searcher
@@ -317,11 +357,6 @@ class GoalPlannerModule : public SceneModuleInterface
317
357
318
358
autoware::universe_utils::LinearRing2d vehicle_footprint_;
319
359
320
- std::recursive_mutex mutex_;
321
- mutable ThreadSafeData thread_safe_data_;
322
-
323
- // TODO(soblin): organize part of thread_safe_data and previous data to PullOverContextData
324
- // context_data_ is initialized in updateData(), used in plan() and refreshed in postProcess()
325
360
std::optional<PullOverContextData> context_data_{std::nullopt};
326
361
// path_decision_controller is updated in updateData(), and used in plan()
327
362
PathDecisionStateController path_decision_controller_{getLogger ()};
@@ -369,12 +404,7 @@ class GoalPlannerModule : public SceneModuleInterface
369
404
// status
370
405
bool hasFinishedCurrentPath (const PullOverContextData & ctx_data);
371
406
double calcModuleRequestLength () const ;
372
- bool isStuck (
373
- const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
374
- const std::shared_ptr<const PlannerData> planner_data,
375
- const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
376
- const GoalPlannerParameters & parameters);
377
- void decideVelocity ();
407
+ void decideVelocity (PullOverPath & pull_over_path);
378
408
void updateStatus (const BehaviorModuleOutput & output);
379
409
380
410
// validation
@@ -385,21 +415,13 @@ class GoalPlannerModule : public SceneModuleInterface
385
415
bool isCrossingPossible (
386
416
const Pose & start_pose, const Pose & end_pose, const lanelet::ConstLanelets lanes) const ;
387
417
bool isCrossingPossible (const PullOverPath & pull_over_path) const ;
388
- bool hasEnoughTimePassedSincePathUpdate (const double duration) const ;
389
-
390
- // freespace parking
391
- bool planFreespacePath (
392
- std::shared_ptr<const PlannerData> planner_data,
393
- const std::shared_ptr<GoalSearcherBase> goal_searcher, const GoalCandidates & goal_candidates,
394
- const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
395
- const PredictedObjects & static_target_objects);
396
418
bool canReturnToLaneParking (const PullOverContextData & context_data);
397
419
398
420
// plan pull over path
399
- BehaviorModuleOutput planPullOver (const PullOverContextData & context_data);
400
- BehaviorModuleOutput planPullOverAsOutput (const PullOverContextData & context_data);
421
+ BehaviorModuleOutput planPullOver (PullOverContextData & context_data);
422
+ BehaviorModuleOutput planPullOverAsOutput (PullOverContextData & context_data);
401
423
BehaviorModuleOutput planPullOverAsCandidate (
402
- const PullOverContextData & context_data, const std::string & detail);
424
+ PullOverContextData & context_data, const std::string & detail);
403
425
std::optional<PullOverPath> selectPullOverPath (
404
426
const PullOverContextData & context_data,
405
427
const std::vector<PullOverPath> & pull_over_path_candidates,
@@ -411,7 +433,9 @@ class GoalPlannerModule : public SceneModuleInterface
411
433
const PullOverContextData & context_data, BehaviorModuleOutput & output) const ;
412
434
413
435
// output setter
414
- void setOutput (const PullOverContextData & context_data, BehaviorModuleOutput & output);
436
+ void setOutput (
437
+ const std::optional<PullOverPath> selected_pull_over_path_with_velocity_opt,
438
+ const PullOverContextData & context_data, BehaviorModuleOutput & output);
415
439
416
440
void setModifiedGoal (
417
441
const PullOverContextData & context_data, BehaviorModuleOutput & output) const ;
@@ -421,10 +445,6 @@ class GoalPlannerModule : public SceneModuleInterface
421
445
TurnSignalInfo calcTurnSignalInfo (const PullOverContextData & context_data);
422
446
std::optional<lanelet::Id> ignore_signal_{std::nullopt};
423
447
424
- // timer for generating pull over path candidates in a separate thread
425
- void onTimer ();
426
- void onFreespaceParkingTimer ();
427
-
428
448
// steering factor
429
449
void updateSteeringFactor (
430
450
const PullOverContextData & context_data, const std::array<Pose, 2 > & pose,
0 commit comments