Skip to content

Commit 45dbbbd

Browse files
soblin0x126
authored andcommitted
fix(start_planner): consider backward completion before preparing blinker (autowarefoundation#6558)
consider backward completion Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent df33eb0 commit 45dbbbd

File tree

2 files changed

+14
-11
lines changed

2 files changed

+14
-11
lines changed

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,9 @@ struct PullOutStatus
7070
std::shared_ptr<PathWithLaneId> prev_stop_path_after_approval{nullptr};
7171
bool has_stop_point{false};
7272
std::optional<Pose> stop_pose{std::nullopt};
73-
//! record the first time when the state changed from !isActivated() to isActivated()
74-
std::optional<rclcpp::Time> first_engaged_time{std::nullopt};
73+
//! record the first time when ego started forward-driving (maybe after backward driving
74+
//! completion) in AUTONOMOUS operation mode
75+
std::optional<rclcpp::Time> first_engaged_and_driving_forward_time{std::nullopt};
7576

7677
PullOutStatus() {}
7778
};
@@ -231,7 +232,7 @@ class StartPlannerModule : public SceneModuleInterface
231232
void updateStatusAfterBackwardDriving();
232233
PredictedObjects filterStopObjectsInPullOutLanes(
233234
const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const;
234-
bool needToPrepareBlinkerBeforeStart() const;
235+
bool needToPrepareBlinkerBeforeStartDrivingForward() const;
235236
bool hasFinishedPullOut() const;
236237
bool hasFinishedBackwardDriving() const;
237238
bool hasCollisionWithDynamicObjects() const;

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,7 @@ void StartPlannerModule::onFreespacePlannerTimer()
104104
BehaviorModuleOutput StartPlannerModule::run()
105105
{
106106
updateData();
107-
if (!isActivated() || needToPrepareBlinkerBeforeStart()) {
107+
if (!isActivated() || needToPrepareBlinkerBeforeStartDrivingForward()) {
108108
return planWaitingApproval();
109109
}
110110

@@ -163,8 +163,8 @@ void StartPlannerModule::updateData()
163163

164164
if (
165165
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();
168168
}
169169

170170
if (hasFinishedBackwardDriving()) {
@@ -968,13 +968,15 @@ bool StartPlannerModule::hasFinishedPullOut() const
968968
return has_finished;
969969
}
970970

971-
bool StartPlannerModule::needToPrepareBlinkerBeforeStart() const
971+
bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward() const
972972
{
973-
if (!status_.first_engaged_time) {
974-
return true;
973+
if (!status_.first_engaged_and_driving_forward_time) {
974+
return false;
975975
}
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();
978980
return elapsed < parameters_->prepare_time_before_start;
979981
}
980982

0 commit comments

Comments
 (0)