Skip to content

Commit 1bbbb2a

Browse files
authored
fix(start_planner): consider backward completion before preparing blinker (#6558)
consider backward completion Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 07a84d4 commit 1bbbb2a

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
bool prev_is_safe_dynamic_objects{false};
7171
std::shared_ptr<PathWithLaneId> prev_stop_path_after_approval{nullptr};
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
};
@@ -279,7 +280,7 @@ class StartPlannerModule : public SceneModuleInterface
279280
const lanelet::ConstLanelets & pull_out_lanes, const geometry_msgs::msg::Point & current_pose,
280281
const double velocity_threshold, const double object_check_backward_distance,
281282
const double object_check_forward_distance) const;
282-
bool needToPrepareBlinkerBeforeStart() const;
283+
bool needToPrepareBlinkerBeforeStartDrivingForward() const;
283284
bool hasFinishedPullOut() const;
284285
bool hasFinishedBackwardDriving() const;
285286
bool hasCollisionWithDynamicObjects() const;

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ void StartPlannerModule::onFreespacePlannerTimer()
119119
BehaviorModuleOutput StartPlannerModule::run()
120120
{
121121
updateData();
122-
if (!isActivated() || needToPrepareBlinkerBeforeStart()) {
122+
if (!isActivated() || needToPrepareBlinkerBeforeStartDrivingForward()) {
123123
return planWaitingApproval();
124124
}
125125

@@ -179,8 +179,8 @@ void StartPlannerModule::updateData()
179179

180180
if (
181181
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();
184184
}
185185

186186
status_.backward_driving_complete = hasFinishedBackwardDriving();
@@ -1179,13 +1179,15 @@ bool StartPlannerModule::hasFinishedPullOut() const
11791179
return has_finished;
11801180
}
11811181

1182-
bool StartPlannerModule::needToPrepareBlinkerBeforeStart() const
1182+
bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward() const
11831183
{
1184-
if (!status_.first_engaged_time) {
1185-
return true;
1184+
if (!status_.first_engaged_and_driving_forward_time) {
1185+
return false;
11861186
}
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();
11891191
return elapsed < parameters_->prepare_time_before_start;
11901192
}
11911193

0 commit comments

Comments
 (0)