Skip to content

Commit

Permalink
fix(start_planner): consider backward completion before preparing bli…
Browse files Browse the repository at this point in the history
…nker (autowarefoundation#6558)

consider backward completion

Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin authored and 0x126 committed Mar 11, 2024
1 parent df33eb0 commit 45dbbbd
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,9 @@ struct PullOutStatus
std::shared_ptr<PathWithLaneId> prev_stop_path_after_approval{nullptr};
bool has_stop_point{false};
std::optional<Pose> stop_pose{std::nullopt};
//! record the first time when the state changed from !isActivated() to isActivated()
std::optional<rclcpp::Time> 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<rclcpp::Time> first_engaged_and_driving_forward_time{std::nullopt};

PullOutStatus() {}
};
Expand Down Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ void StartPlannerModule::onFreespacePlannerTimer()
BehaviorModuleOutput StartPlannerModule::run()
{
updateData();
if (!isActivated() || needToPrepareBlinkerBeforeStart()) {
if (!isActivated() || needToPrepareBlinkerBeforeStartDrivingForward()) {
return planWaitingApproval();
}

Expand Down Expand Up @@ -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()) {
Expand Down Expand Up @@ -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;
}

Expand Down

0 comments on commit 45dbbbd

Please sign in to comment.