Skip to content

Commit 8580577

Browse files
authored
Merge pull request #1162 from tier4/cherry-pick/pr6438+6470
Cherry pick/pr6438+6470 + 6558
2 parents 0a8cc23 + 45dbbbd commit 8580577

File tree

5 files changed

+27
-1
lines changed

5 files changed

+27
-1
lines changed

planning/behavior_path_start_planner_module/config/start_planner.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
backward_path_update_duration: 3.0
3737
ignore_distance_from_lane_end: 15.0
3838
# turns signal
39+
prepare_time_before_start: 0.0
3940
th_turn_signal_on_lateral_offset: 1.0
4041
intersection_search_length: 30.0
4142
length_ratio_for_turn_signal_deactivation_near_intersection: 0.5

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,10 @@ struct PullOutStatus
6969
bool prev_is_safe_dynamic_objects{false};
7070
std::shared_ptr<PathWithLaneId> prev_stop_path_after_approval{nullptr};
7171
bool has_stop_point{false};
72+
std::optional<Pose> stop_pose{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};
7276

7377
PullOutStatus() {}
7478
};
@@ -228,6 +232,7 @@ class StartPlannerModule : public SceneModuleInterface
228232
void updateStatusAfterBackwardDriving();
229233
PredictedObjects filterStopObjectsInPullOutLanes(
230234
const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const;
235+
bool needToPrepareBlinkerBeforeStartDrivingForward() const;
231236
bool hasFinishedPullOut() const;
232237
bool hasFinishedBackwardDriving() const;
233238
bool hasCollisionWithDynamicObjects() const;

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@ struct StartPlannerParameters
3838
double th_arrived_distance{0.0};
3939
double th_stopped_velocity{0.0};
4040
double th_stopped_time{0.0};
41+
double prepare_time_before_start{0.0};
4142
double th_turn_signal_on_lateral_offset{0.0};
4243
double th_distance_to_middle_of_the_road{0.0};
4344
double intersection_search_length{0.0};

planning/behavior_path_start_planner_module/src/manager.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
3636
p.th_arrived_distance = node->declare_parameter<double>(ns + "th_arrived_distance");
3737
p.th_stopped_velocity = node->declare_parameter<double>(ns + "th_stopped_velocity");
3838
p.th_stopped_time = node->declare_parameter<double>(ns + "th_stopped_time");
39+
p.prepare_time_before_start = node->declare_parameter<double>(ns + "prepare_time_before_start");
3940
p.th_turn_signal_on_lateral_offset =
4041
node->declare_parameter<double>(ns + "th_turn_signal_on_lateral_offset");
4142
p.th_distance_to_middle_of_the_road =

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+19-1
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()) {
107+
if (!isActivated() || needToPrepareBlinkerBeforeStartDrivingForward()) {
108108
return planWaitingApproval();
109109
}
110110

@@ -161,6 +161,12 @@ void StartPlannerModule::updateData()
161161
DEBUG_PRINT("StartPlannerModule::updateData() received new route, reset status");
162162
}
163163

164+
if (
165+
planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS &&
166+
status_.driving_forward && !status_.first_engaged_and_driving_forward_time) {
167+
status_.first_engaged_and_driving_forward_time = clock_->now();
168+
}
169+
164170
if (hasFinishedBackwardDriving()) {
165171
updateStatusAfterBackwardDriving();
166172
DEBUG_PRINT("StartPlannerModule::updateData() completed backward driving");
@@ -962,6 +968,18 @@ bool StartPlannerModule::hasFinishedPullOut() const
962968
return has_finished;
963969
}
964970

971+
bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward() const
972+
{
973+
if (!status_.first_engaged_and_driving_forward_time) {
974+
return false;
975+
}
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();
980+
return elapsed < parameters_->prepare_time_before_start;
981+
}
982+
965983
bool StartPlannerModule::isStuck()
966984
{
967985
if (!isStopped()) {

0 commit comments

Comments
 (0)