@@ -104,7 +104,7 @@ void StartPlannerModule::onFreespacePlannerTimer()
104
104
BehaviorModuleOutput StartPlannerModule::run ()
105
105
{
106
106
updateData ();
107
- if (!isActivated () || needToPrepareBlinkerBeforeStart ()) {
107
+ if (!isActivated () || needToPrepareBlinkerBeforeStartDrivingForward ()) {
108
108
return planWaitingApproval ();
109
109
}
110
110
@@ -163,8 +163,8 @@ void StartPlannerModule::updateData()
163
163
164
164
if (
165
165
planner_data_->operation_mode ->mode == OperationModeState::AUTONOMOUS &&
166
- !status_.first_engaged_time ) {
167
- status_.first_engaged_time = clock_->now ();
166
+ status_. driving_forward && !status_.first_engaged_and_driving_forward_time ) {
167
+ status_.first_engaged_and_driving_forward_time = clock_->now ();
168
168
}
169
169
170
170
if (hasFinishedBackwardDriving ()) {
@@ -968,13 +968,15 @@ bool StartPlannerModule::hasFinishedPullOut() const
968
968
return has_finished;
969
969
}
970
970
971
- bool StartPlannerModule::needToPrepareBlinkerBeforeStart () const
971
+ bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward () const
972
972
{
973
- if (!status_.first_engaged_time ) {
974
- return true ;
973
+ if (!status_.first_engaged_and_driving_forward_time ) {
974
+ return false ;
975
975
}
976
- const auto first_engaged_time = status_.first_engaged_time .value ();
977
- const double elapsed = rclcpp::Duration (clock_->now () - first_engaged_time).seconds ();
976
+ const auto first_engaged_and_driving_forward_time =
977
+ status_.first_engaged_and_driving_forward_time .value ();
978
+ const double elapsed =
979
+ rclcpp::Duration (clock_->now () - first_engaged_and_driving_forward_time).seconds ();
978
980
return elapsed < parameters_->prepare_time_before_start ;
979
981
}
980
982
0 commit comments