@@ -110,15 +110,22 @@ struct PullOverContextData
110
110
PullOverContextData () = delete ;
111
111
explicit PullOverContextData (
112
112
const bool is_stable_safe_path, const PredictedObjects & static_objects,
113
- const PredictedObjects & dynamic_objects)
113
+ const PredictedObjects & dynamic_objects, std::optional<PullOverPath> && pull_over_path_opt,
114
+ const std::vector<PullOverPath> & pull_over_path_candidates)
114
115
: is_stable_safe_path(is_stable_safe_path),
115
116
static_target_objects(static_objects),
116
- dynamic_target_objects(dynamic_objects)
117
+ dynamic_target_objects(dynamic_objects),
118
+ pull_over_path_opt(pull_over_path_opt),
119
+ pull_over_path_candidates(pull_over_path_candidates)
117
120
{
118
121
}
119
122
const bool is_stable_safe_path;
120
123
const PredictedObjects static_target_objects;
121
124
const PredictedObjects dynamic_target_objects;
125
+ // TODO(soblin): due to deceleratePath(), this cannot be const member(velocity is modified by it)
126
+ std::optional<PullOverPath> pull_over_path_opt;
127
+ const std::vector<PullOverPath> pull_over_path_candidates;
128
+ // TODO(soblin): goal_candidate_from_thread, modifed_goal_pose_from_thread, closest_start_pose
122
129
};
123
130
124
131
class GoalPlannerModule : public SceneModuleInterface
@@ -354,7 +361,7 @@ class GoalPlannerModule : public SceneModuleInterface
354
361
void decelerateForTurnSignal (const Pose & stop_pose, PathWithLaneId & path) const ;
355
362
void decelerateBeforeSearchStart (
356
363
const Pose & search_start_offset_pose, PathWithLaneId & path) const ;
357
- PathWithLaneId generateStopPath () const ;
364
+ PathWithLaneId generateStopPath (const PullOverContextData & context_data ) const ;
358
365
PathWithLaneId generateFeasibleStopPath (const PathWithLaneId & path) const ;
359
366
360
367
void keepStoppedWithCurrentPath (PathWithLaneId & path) const ;
@@ -364,7 +371,7 @@ class GoalPlannerModule : public SceneModuleInterface
364
371
bool isStopped ();
365
372
bool isStopped (
366
373
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> & odometry_buffer, const double time);
367
- bool hasFinishedCurrentPath ();
374
+ bool hasFinishedCurrentPath (const PullOverContextData & ctx_data );
368
375
bool isOnModifiedGoal (const Pose & current_pose, const GoalPlannerParameters & parameters) const ;
369
376
double calcModuleRequestLength () const ;
370
377
bool needPathUpdate (
@@ -406,16 +413,18 @@ class GoalPlannerModule : public SceneModuleInterface
406
413
407
414
// lanes and drivable area
408
415
std::vector<DrivableLanes> generateDrivableLanes () const ;
409
- void setDrivableAreaInfo (BehaviorModuleOutput & output) const ;
416
+ void setDrivableAreaInfo (
417
+ const PullOverContextData & context_data, BehaviorModuleOutput & output) const ;
410
418
411
419
// output setter
412
420
void setOutput (const PullOverContextData & context_data, BehaviorModuleOutput & output);
413
421
414
- void setModifiedGoal (BehaviorModuleOutput & output) const ;
415
- void setTurnSignalInfo (BehaviorModuleOutput & output);
422
+ void setModifiedGoal (
423
+ const PullOverContextData & context_data, BehaviorModuleOutput & output) const ;
424
+ void setTurnSignalInfo (const PullOverContextData & context_data, BehaviorModuleOutput & output);
416
425
417
426
// new turn signal
418
- TurnSignalInfo calcTurnSignalInfo ();
427
+ TurnSignalInfo calcTurnSignalInfo (const PullOverContextData & context_data );
419
428
std::optional<lanelet::Id> ignore_signal_{std::nullopt};
420
429
421
430
bool hasPreviousModulePathShapeChanged (const BehaviorModuleOutput & previous_module_output) const ;
@@ -431,10 +440,12 @@ class GoalPlannerModule : public SceneModuleInterface
431
440
432
441
// steering factor
433
442
void updateSteeringFactor (
434
- const std::array<Pose, 2 > & pose, const std::array<double , 2 > distance, const uint16_t type);
443
+ const PullOverContextData & context_data, const std::array<Pose, 2 > & pose,
444
+ const std::array<double , 2 > distance, const uint16_t type);
435
445
436
446
// rtc
437
- std::pair<double , double > calcDistanceToPathChange () const ;
447
+ std::pair<double , double > calcDistanceToPathChange (
448
+ const PullOverContextData & context_data) const ;
438
449
439
450
// safety check
440
451
void initializeSafetyCheckParameters ();
0 commit comments