diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index eafe8d02617f7..bf5a64b4d0973 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -70,8 +70,9 @@ struct PullOutStatus std::shared_ptr prev_stop_path_after_approval{nullptr}; bool has_stop_point{false}; std::optional stop_pose{std::nullopt}; - //! record the first time when the state changed from !isActivated() to isActivated() - std::optional first_engaged_time{std::nullopt}; + //! record the first time when ego started forward-driving (maybe after backward driving + //! completion) in AUTONOMOUS operation mode + std::optional first_engaged_and_driving_forward_time{std::nullopt}; PullOutStatus() {} }; @@ -231,7 +232,7 @@ class StartPlannerModule : public SceneModuleInterface void updateStatusAfterBackwardDriving(); PredictedObjects filterStopObjectsInPullOutLanes( const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const; - bool needToPrepareBlinkerBeforeStart() const; + bool needToPrepareBlinkerBeforeStartDrivingForward() const; bool hasFinishedPullOut() const; bool hasFinishedBackwardDriving() const; bool hasCollisionWithDynamicObjects() const; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 338082e7d3c01..1eb5aa9191a5c 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -104,7 +104,7 @@ void StartPlannerModule::onFreespacePlannerTimer() BehaviorModuleOutput StartPlannerModule::run() { updateData(); - if (!isActivated() || needToPrepareBlinkerBeforeStart()) { + if (!isActivated() || needToPrepareBlinkerBeforeStartDrivingForward()) { return planWaitingApproval(); } @@ -163,8 +163,8 @@ void StartPlannerModule::updateData() if ( planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS && - !status_.first_engaged_time) { - status_.first_engaged_time = clock_->now(); + status_.driving_forward && !status_.first_engaged_and_driving_forward_time) { + status_.first_engaged_and_driving_forward_time = clock_->now(); } if (hasFinishedBackwardDriving()) { @@ -968,13 +968,15 @@ bool StartPlannerModule::hasFinishedPullOut() const return has_finished; } -bool StartPlannerModule::needToPrepareBlinkerBeforeStart() const +bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward() const { - if (!status_.first_engaged_time) { - return true; + if (!status_.first_engaged_and_driving_forward_time) { + return false; } - const auto first_engaged_time = status_.first_engaged_time.value(); - const double elapsed = rclcpp::Duration(clock_->now() - first_engaged_time).seconds(); + const auto first_engaged_and_driving_forward_time = + status_.first_engaged_and_driving_forward_time.value(); + const double elapsed = + rclcpp::Duration(clock_->now() - first_engaged_and_driving_forward_time).seconds(); return elapsed < parameters_->prepare_time_before_start; }