Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(start_planner): consider backward completion before preparing blinker (#6558) #1183

Merged
merged 1 commit into from
Mar 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,9 @@ struct PullOutStatus
bool prev_is_safe_dynamic_objects{false};
std::shared_ptr<PathWithLaneId> prev_stop_path_after_approval{nullptr};
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 @@ -278,7 +279,7 @@ class StartPlannerModule : public SceneModuleInterface
const lanelet::ConstLanelets & pull_out_lanes, const geometry_msgs::msg::Point & current_pose,
const double velocity_threshold, const double object_check_backward_distance,
const double object_check_forward_distance) 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 @@ -118,7 +118,7 @@ void StartPlannerModule::onFreespacePlannerTimer()
BehaviorModuleOutput StartPlannerModule::run()
{
updateData();
if (!isActivated() || needToPrepareBlinkerBeforeStart()) {
if (!isActivated() || needToPrepareBlinkerBeforeStartDrivingForward()) {
return planWaitingApproval();
}

Expand Down Expand Up @@ -178,8 +178,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();
}

status_.backward_driving_complete = hasFinishedBackwardDriving();
Expand Down Expand Up @@ -1073,13 +1073,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
Loading