Skip to content

Commit 1511d1d

Browse files
feat(lane_change): cancel hysteresis (autowarefoundation#6288)
* feat(lane_change): cancel hysteresis Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Update documentation Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix the explanation of the hysteresis count Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 8de50de commit 1511d1d

File tree

8 files changed

+71
-1
lines changed

8 files changed

+71
-1
lines changed

planning/behavior_path_lane_change_module/README.md

+24
Original file line numberDiff line numberDiff line change
@@ -284,6 +284,29 @@ detach
284284
@enduml
285285
```
286286

287+
To preventive measure for lane change path oscillations caused by alternating safe and unsafe conditions, an additional hysteresis count check is implemented before executing an abort or cancel maneuver. If unsafe, the `unsafe_hysteresis_count_` is incremented and compared against `unsafe_hysteresis_threshold`; exceeding it prompts an abort condition check, ensuring decisions are made with consideration to recent safety assessments as shown in flow chart above. This mechanism stabilizes decision-making, preventing abrupt changes due to transient unsafe conditions.
288+
289+
```plantuml
290+
@startuml
291+
skinparam defaultTextAlignment center
292+
skinparam backgroundColor #WHITE
293+
294+
title Abort Lane Change
295+
296+
if (Perform collision check?) then (<color:green><b>SAFE</b></color>)
297+
:Reset unsafe_hysteresis_count_;
298+
else (<color:red><b>UNSAFE</b></color>)
299+
:Increase unsafe_hysteresis_count_;
300+
if (unsafe_hysteresis_count_ > unsafe_hysteresis_threshold?) then (<color:green><b>FALSE</b></color>)
301+
else (<color:red><b>TRUE</b></color>)
302+
#LightPink:Check abort condition;
303+
stop
304+
endif
305+
endif
306+
:Continue lane changing;
307+
@enduml
308+
```
309+
287310
#### Cancel
288311

289312
Suppose the lane change trajectory is evaluated as unsafe. In that case, if the ego vehicle has not departed from the current lane yet, the trajectory will be reset, and the ego vehicle will resume the lane following the maneuver.
@@ -423,6 +446,7 @@ The following parameters are configurable in `lane_change.param.yaml`.
423446
| `cancel.duration` | [s] | double | The time taken to complete returning to the center line. | 3.0 |
424447
| `cancel.max_lateral_jerk` | [m/sss] | double | The maximum lateral jerk for abort path | 1000.0 |
425448
| `cancel.overhang_tolerance` | [m] | double | Lane change cancel is prohibited if the vehicle head exceeds the lane boundary more than this tolerance distance | 0.0 |
449+
| `unsafe_hysteresis_threshold` | [-] | int | threshold that helps prevent frequent switching between safe and unsafe decisions | 10 |
426450

427451
### Debug
428452

planning/behavior_path_lane_change_module/config/lane_change.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,7 @@
103103
duration: 5.0 # [s]
104104
max_lateral_jerk: 1000.0 # [m/s3]
105105
overhang_tolerance: 0.0 # [m]
106+
unsafe_hysteresis_threshold: 10 # [/]
106107

107108
finish_judge_lateral_threshold: 0.2 # [m]
108109

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_
1616

1717
#include "behavior_path_lane_change_module/utils/base_class.hpp"
18+
#include "behavior_path_lane_change_module/utils/data_structs.hpp"
1819

1920
#include <memory>
2021
#include <utility>
@@ -73,6 +74,9 @@ class NormalLaneChange : public LaneChangeBase
7374

7475
PathSafetyStatus isApprovedPathSafe() const override;
7576

77+
PathSafetyStatus evaluateApprovedPathWithUnsafeHysteresis(
78+
PathSafetyStatus approved_path_safety_status) override;
79+
7680
bool isRequiredStop(const bool is_object_coming_from_rear) override;
7781

7882
bool isNearEndOfCurrentLanes(

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,9 @@ class LaneChangeBase
9696

9797
virtual PathSafetyStatus isApprovedPathSafe() const = 0;
9898

99+
virtual PathSafetyStatus evaluateApprovedPathWithUnsafeHysteresis(
100+
PathSafetyStatus approve_path_safety_status) = 0;
101+
99102
virtual bool isNearEndOfCurrentLanes(
100103
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
101104
const double threshold) const = 0;
@@ -240,6 +243,7 @@ class LaneChangeBase
240243

241244
PathWithLaneId prev_approved_path_{};
242245

246+
int unsafe_hysteresis_count_{0};
243247
bool is_abort_path_approved_{false};
244248
bool is_abort_approval_requested_{false};
245249
bool is_activated_{false};

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,11 @@ struct LaneChangeCancelParameters
7575
double duration{5.0};
7676
double max_lateral_jerk{10.0};
7777
double overhang_tolerance{0.0};
78+
79+
// unsafe_hysteresis_threshold will be compare with the number of detected unsafe instance. If the
80+
// number of unsafe exceeds unsafe_hysteresis_threshold, the lane change will be cancelled or
81+
// aborted.
82+
int unsafe_hysteresis_threshold{2};
7883
};
7984

8085
struct LaneChangeParameters

planning/behavior_path_lane_change_module/src/interface.cpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,7 @@ void LaneChangeInterface::processOnExit()
5656
{
5757
module_type_->resetParameters();
5858
debug_marker_.markers.clear();
59+
post_process_safety_status_ = {};
5960
resetPathCandidate();
6061
}
6162

@@ -91,7 +92,11 @@ void LaneChangeInterface::updateData()
9192

9293
void LaneChangeInterface::postProcess()
9394
{
94-
post_process_safety_status_ = module_type_->isApprovedPathSafe();
95+
if (getCurrentStatus() == ModuleStatus::RUNNING) {
96+
const auto safety_status = module_type_->isApprovedPathSafe();
97+
post_process_safety_status_ =
98+
module_type_->evaluateApprovedPathWithUnsafeHysteresis(safety_status);
99+
}
95100
}
96101

97102
BehaviorModuleOutput LaneChangeInterface::plan()

planning/behavior_path_lane_change_module/src/manager.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -215,6 +215,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
215215
getOrDeclareParameter<double>(*node, parameter("cancel.max_lateral_jerk"));
216216
p.cancel.overhang_tolerance =
217217
getOrDeclareParameter<double>(*node, parameter("cancel.overhang_tolerance"));
218+
p.cancel.unsafe_hysteresis_threshold =
219+
getOrDeclareParameter<int>(*node, parameter("cancel.unsafe_hysteresis_threshold"));
218220

219221
p.finish_judge_lateral_threshold =
220222
getOrDeclareParameter<double>(*node, parameter("finish_judge_lateral_threshold"));
@@ -376,6 +378,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
376378
updateParam<double>(parameters, ns + "duration", p->cancel.duration);
377379
updateParam<double>(parameters, ns + "max_lateral_jerk", p->cancel.max_lateral_jerk);
378380
updateParam<double>(parameters, ns + "overhang_tolerance", p->cancel.overhang_tolerance);
381+
updateParam<int>(
382+
parameters, ns + "unsafe_hysteresis_threshold", p->cancel.unsafe_hysteresis_threshold);
379383
}
380384
std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) {
381385
if (!observer.expired()) observer.lock()->updateModuleParams(p);

planning/behavior_path_lane_change_module/src/scene.cpp

+23
Original file line numberDiff line numberDiff line change
@@ -474,6 +474,7 @@ void NormalLaneChange::resetParameters()
474474
current_lane_change_state_ = LaneChangeStates::Normal;
475475
abort_path_ = nullptr;
476476
status_ = {};
477+
unsafe_hysteresis_count_ = 0;
477478
lane_change_debug_.reset();
478479

479480
RCLCPP_DEBUG(logger_, "reset all flags and debug information.");
@@ -1665,6 +1666,28 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
16651666
return safety_status;
16661667
}
16671668

1669+
PathSafetyStatus NormalLaneChange::evaluateApprovedPathWithUnsafeHysteresis(
1670+
PathSafetyStatus approved_path_safety_status)
1671+
{
1672+
if (!approved_path_safety_status.is_safe) {
1673+
++unsafe_hysteresis_count_;
1674+
RCLCPP_DEBUG(
1675+
logger_, "%s: Increasing hysteresis count to %d.", __func__, unsafe_hysteresis_count_);
1676+
} else {
1677+
if (unsafe_hysteresis_count_ > 0) {
1678+
RCLCPP_DEBUG(logger_, "%s: Lane change is now SAFE. Resetting hysteresis count.", __func__);
1679+
}
1680+
unsafe_hysteresis_count_ = 0;
1681+
}
1682+
if (unsafe_hysteresis_count_ > lane_change_parameters_->cancel.unsafe_hysteresis_threshold) {
1683+
RCLCPP_DEBUG(
1684+
logger_, "%s: hysteresis count exceed threshold. lane change is now %s", __func__,
1685+
(approved_path_safety_status.is_safe ? "safe" : "UNSAFE"));
1686+
return approved_path_safety_status;
1687+
}
1688+
return {};
1689+
}
1690+
16681691
TurnSignalInfo NormalLaneChange::calcTurnSignalInfo() const
16691692
{
16701693
const auto get_blinker_pose = [](const PathWithLaneId & path, const double length) {

0 commit comments

Comments
 (0)