@@ -119,7 +119,7 @@ void StartPlannerModule::onFreespacePlannerTimer()
119
119
BehaviorModuleOutput StartPlannerModule::run ()
120
120
{
121
121
updateData ();
122
- if (!isActivated () || needToPrepareBlinkerBeforeStart ()) {
122
+ if (!isActivated () || needToPrepareBlinkerBeforeStartDrivingForward ()) {
123
123
return planWaitingApproval ();
124
124
}
125
125
@@ -179,8 +179,8 @@ void StartPlannerModule::updateData()
179
179
180
180
if (
181
181
planner_data_->operation_mode ->mode == OperationModeState::AUTONOMOUS &&
182
- !status_.first_engaged_time ) {
183
- status_.first_engaged_time = clock_->now ();
182
+ status_. driving_forward && !status_.first_engaged_and_driving_forward_time ) {
183
+ status_.first_engaged_and_driving_forward_time = clock_->now ();
184
184
}
185
185
186
186
status_.backward_driving_complete = hasFinishedBackwardDriving ();
@@ -1179,13 +1179,15 @@ bool StartPlannerModule::hasFinishedPullOut() const
1179
1179
return has_finished;
1180
1180
}
1181
1181
1182
- bool StartPlannerModule::needToPrepareBlinkerBeforeStart () const
1182
+ bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward () const
1183
1183
{
1184
- if (!status_.first_engaged_time ) {
1185
- return true ;
1184
+ if (!status_.first_engaged_and_driving_forward_time ) {
1185
+ return false ;
1186
1186
}
1187
- const auto first_engaged_time = status_.first_engaged_time .value ();
1188
- const double elapsed = rclcpp::Duration (clock_->now () - first_engaged_time).seconds ();
1187
+ const auto first_engaged_and_driving_forward_time =
1188
+ status_.first_engaged_and_driving_forward_time .value ();
1189
+ const double elapsed =
1190
+ rclcpp::Duration (clock_->now () - first_engaged_and_driving_forward_time).seconds ();
1189
1191
return elapsed < parameters_->prepare_time_before_start ;
1190
1192
}
1191
1193
0 commit comments