Skip to content

Commit f6de32d

Browse files
make code of similar to main branch
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent c734d1a commit f6de32d

File tree

9 files changed

+79
-65
lines changed

9 files changed

+79
-65
lines changed

planning/behavior_path_lane_change_module/config/lane_change.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@
66

77
backward_length_buffer_for_end_of_lane: 3.0 # [m]
88
backward_length_buffer_for_blocking_object: 3.0 # [m]
9+
backward_length_from_intersection: 5.0 # [m]
10+
911
lane_change_finish_judge_buffer: 2.0 # [m]
1012

1113
lane_changing_lateral_jerk: 0.5 # [m/s3]

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -98,8 +98,6 @@ class NormalLaneChange : public LaneChangeBase
9898

9999
bool isStoppedAtRedTrafficLight() const override;
100100

101-
bool is_safe_to_try_change_lanes_at_intersection() const final;
102-
103101
protected:
104102
lanelet::ConstLanelets getCurrentLanes() const override;
105103

@@ -188,6 +186,9 @@ class NormalLaneChange : public LaneChangeBase
188186

189187
double getStopTime() const { return stop_time_; }
190188

189+
void update_dist_from_intersection();
190+
191+
std::vector<PathPointWithLaneId> path_after_intersection_;
191192
double stop_time_{0.0};
192193
};
193194
} // namespace behavior_path_planner

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

-2
Original file line numberDiff line numberDiff line change
@@ -84,8 +84,6 @@ class LaneChangeBase
8484

8585
virtual bool isAbortState() const = 0;
8686

87-
virtual bool is_safe_to_try_change_lanes_at_intersection() const = 0;
88-
8987
virtual bool isAbleToReturnCurrentLane() const = 0;
9088

9189
virtual LaneChangePath getLaneChangePath() const = 0;

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -40,19 +40,18 @@ using LaneChangePaths = std::vector<LaneChangePath>;
4040
struct LaneChangeStatus
4141
{
4242
PathWithLaneId lane_follow_path{};
43-
PathWithLaneId path_after_intersection{};
4443
LaneChangePath lane_change_path{};
4544
lanelet::ConstLanelets current_lanes{};
4645
lanelet::ConstLanelets target_lanes{};
47-
lanelet::ConstLanelet current_lane_{};
46+
lanelet::ConstLanelet current_lane{};
4847
std::vector<lanelet::Id> lane_follow_lane_ids{};
4948
std::vector<lanelet::Id> lane_change_lane_ids{};
5049
bool is_safe{false};
5150
bool is_valid_path{true};
5251
bool is_ego_in_turn_direction_lane{false};
5352
bool is_ego_in_intersection{false};
5453
double start_distance{0.0};
55-
double distance_from_prev_intersection{std::numeric_limits<double>::max()};
54+
double dist_from_prev_intersection{std::numeric_limits<double>::max()};
5655
};
5756

5857
} // namespace behavior_path_planner

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

+4-1
Original file line numberDiff line numberDiff line change
@@ -340,10 +340,13 @@ bool has_blocking_target_object(
340340
const LaneChangeParameters & lc_param, const double stop_arc_length, const Pose & ego_pose,
341341
const PathWithLaneId & path);
342342

343+
bool has_passed_intersection_turn_direction(
344+
const LaneChangeParameters & lc_param, const LaneChangeStatus & status);
345+
343346
std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject & object);
344347

345348
bool has_overtaking_turn_lane_object(
346-
const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelet & ego_current_lane,
349+
const LaneChangeStatus & status, const LaneChangeParameters & lc_param,
347350
const ExtendedPredictedObjects & trailing_objects);
348351
} // namespace behavior_path_planner::utils::lane_change
349352
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_lane_change_module/src/interface.cpp

-8
Original file line numberDiff line numberDiff line change
@@ -121,14 +121,6 @@ ModuleStatus LaneChangeInterface::updateState()
121121

122122
setObjectDebugVisualization();
123123

124-
if (
125-
!module_type_->is_safe_to_try_change_lanes_at_intersection() &&
126-
module_type_->isAbleToReturnCurrentLane()) {
127-
RCLCPP_DEBUG(
128-
logger_, "unsafe to try lane change at intersection but able to return to current lane");
129-
return ModuleStatus::SUCCESS;
130-
}
131-
132124
if (is_safe) {
133125
log_warn_throttled("Lane change path is safe.");
134126
module_type_->toNormalState();

planning/behavior_path_lane_change_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -169,6 +169,8 @@ void LaneChangeModuleManager::init(rclcpp::Node * node)
169169
getOrDeclareParameter<double>(*node, parameter("backward_length_buffer_for_end_of_lane"));
170170
p.backward_length_buffer_for_blocking_object =
171171
getOrDeclareParameter<double>(*node, parameter("backward_length_buffer_for_blocking_object"));
172+
p.backward_length_from_intersection =
173+
getOrDeclareParameter<double>(*node, parameter("backward_length_from_intersection"));
172174
p.lane_changing_lateral_jerk =
173175
getOrDeclareParameter<double>(*node, parameter("lane_changing_lateral_jerk"));
174176
p.lane_change_prepare_duration =

planning/behavior_path_lane_change_module/src/scene.cpp

+45-48
Original file line numberDiff line numberDiff line change
@@ -73,32 +73,8 @@ void NormalLaneChange::updateLaneChangeStatus()
7373
status_.is_ego_in_intersection =
7474
utils::lane_change::isWithinIntersection(getRouteHandler(), current_lane, ego_footprint);
7575

76-
if (
77-
status_.is_ego_in_intersection && status_.is_ego_in_turn_direction_lane &&
78-
status_.path_after_intersection.points.empty()) {
79-
const auto target_neighbor =
80-
utils::lane_change::getTargetNeighborLanes(*getRouteHandler(), status_.current_lanes, type_);
81-
status_.path_after_intersection = getRouteHandler()->getCenterLinePath(
82-
target_neighbor, 0.0, std::numeric_limits<double>::max());
83-
status_.distance_from_prev_intersection = 0.0;
84-
}
76+
update_dist_from_intersection();
8577

86-
if (
87-
!status_.is_ego_in_intersection && !status_.is_ego_in_turn_direction_lane &&
88-
!status_.path_after_intersection.points.empty()) {
89-
status_.distance_from_prev_intersection = calcSignedArcLength(
90-
status_.path_after_intersection.points,
91-
status_.path_after_intersection.points.front().point.pose.position, getEgoPosition());
92-
}
93-
94-
if (
95-
!status_.is_ego_in_intersection && !status_.is_ego_in_turn_direction_lane &&
96-
status_.distance_from_prev_intersection >
97-
lane_change_parameters_->backward_length_from_intersection &&
98-
!status_.path_after_intersection.points.empty()) {
99-
status_.path_after_intersection = PathWithLaneId();
100-
status_.distance_from_prev_intersection = std::numeric_limits<double>::max();
101-
}
10278
const auto [found_valid_path, found_safe_path] = getSafePath(status_.lane_change_path);
10379

10480
// Update status
@@ -180,24 +156,6 @@ bool NormalLaneChange::isStoppedAtRedTrafficLight() const
180156
status_.lane_change_path.info.length.sum());
181157
}
182158

183-
bool NormalLaneChange::is_safe_to_try_change_lanes_at_intersection() const
184-
{
185-
if (debug_filtered_objects_.target_lane.empty() || status_.target_lanes.empty()) {
186-
return true;
187-
}
188-
189-
const auto has_overtaking_turn_direction_object =
190-
utils::lane_change::has_overtaking_turn_lane_object(
191-
status_.target_lanes, status_.current_lane_, debug_filtered_objects_.target_lane);
192-
193-
if (!has_overtaking_turn_direction_object) {
194-
return true;
195-
}
196-
197-
return status_.distance_from_prev_intersection >
198-
lane_change_parameters_->backward_length_from_intersection;
199-
}
200-
201159
LaneChangePath NormalLaneChange::getLaneChangePath() const
202160
{
203161
return status_.lane_change_path;
@@ -1438,11 +1396,8 @@ bool NormalLaneChange::getLaneChangePaths(
14381396
if (status_.is_ego_in_intersection && status_.is_ego_in_turn_direction_lane) {
14391397
return false;
14401398
}
1441-
if (
1442-
status_.distance_from_prev_intersection <
1443-
lane_change_parameters_->backward_length_from_intersection &&
1444-
utils::lane_change::has_overtaking_turn_lane_object(
1445-
status_.target_lanes, status_.current_lane_, target_objects.target_lane)) {
1399+
if (utils::lane_change::has_overtaking_turn_lane_object(
1400+
status_, *lane_change_parameters_, target_objects.target_lane)) {
14461401
RCLCPP_DEBUG(logger_, "has overtaking object while ego leaves intersection");
14471402
return false;
14481403
}
@@ -1490,6 +1445,12 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
14901445
const auto target_objects = getTargetObjects(current_lanes, target_lanes);
14911446
debug_filtered_objects_ = target_objects;
14921447

1448+
const auto has_overtaking_object = utils::lane_change::has_overtaking_turn_lane_object(
1449+
status_, *lane_change_parameters_, target_objects.target_lane);
1450+
1451+
if (has_overtaking_object) {
1452+
return {false, true};
1453+
}
14931454
CollisionCheckDebugMap debug_data;
14941455
const bool is_stuck = isVehicleStuck(current_lanes);
14951456
const auto safety_status = isLaneChangePathSafe(
@@ -1965,4 +1926,40 @@ bool NormalLaneChange::check_prepare_phase() const
19651926
return check_in_intersection || check_in_turns || check_in_general_lanes;
19661927
}
19671928

1929+
void NormalLaneChange::update_dist_from_intersection()
1930+
{
1931+
if (
1932+
status_.is_ego_in_intersection && status_.is_ego_in_turn_direction_lane &&
1933+
path_after_intersection_.empty()) {
1934+
const auto target_neighbor =
1935+
utils::lane_change::getTargetNeighborLanes(*getRouteHandler(), status_.current_lanes, type_);
1936+
auto path_after_intersection = getRouteHandler()->getCenterLinePath(
1937+
target_neighbor, 0.0, std::numeric_limits<double>::max());
1938+
path_after_intersection_ = std::move(path_after_intersection.points);
1939+
status_.dist_from_prev_intersection = 0.0;
1940+
return;
1941+
}
1942+
1943+
if (
1944+
status_.is_ego_in_intersection || status_.is_ego_in_turn_direction_lane ||
1945+
path_after_intersection_.empty()) {
1946+
return;
1947+
}
1948+
1949+
const auto & path_points = path_after_intersection_;
1950+
const auto & front_point = path_points.front().point.pose.position;
1951+
const auto & ego_position = getEgoPosition();
1952+
status_.dist_from_prev_intersection = calcSignedArcLength(path_points, front_point, ego_position);
1953+
1954+
if (
1955+
status_.dist_from_prev_intersection >= 0.0 &&
1956+
status_.dist_from_prev_intersection <=
1957+
lane_change_parameters_->backward_length_from_intersection) {
1958+
return;
1959+
}
1960+
1961+
path_after_intersection_.clear();
1962+
status_.dist_from_prev_intersection = std::numeric_limits<double>::max();
1963+
}
1964+
19681965
} // namespace behavior_path_planner

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+21-1
Original file line numberDiff line numberDiff line change
@@ -1306,6 +1306,16 @@ bool has_blocking_target_object(
13061306
});
13071307
}
13081308

1309+
bool has_passed_intersection_turn_direction(
1310+
const LaneChangeParameters & lc_param, const LaneChangeStatus & status)
1311+
{
1312+
if (status.is_ego_in_intersection && status.is_ego_in_turn_direction_lane) {
1313+
return false;
1314+
}
1315+
1316+
return status.dist_from_prev_intersection > lc_param.backward_length_from_intersection;
1317+
}
1318+
13091319
std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject & object)
13101320
{
13111321
const auto transform = [](const auto & predicted_path) -> LineString2d {
@@ -1328,11 +1338,21 @@ std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject &
13281338
}
13291339

13301340
bool has_overtaking_turn_lane_object(
1331-
const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelet & ego_current_lane,
1341+
const LaneChangeStatus & status, const LaneChangeParameters & lc_param,
13321342
const ExtendedPredictedObjects & trailing_objects)
13331343
{
1344+
// Note: This situation is only applicable if the ego is in a turn lane.
1345+
if (!has_passed_intersection_turn_direction(lc_param, status)) {
1346+
return true;
1347+
}
1348+
1349+
const auto & target_lanes = status.target_lanes;
1350+
const auto & ego_current_lane = status.current_lane;
1351+
13341352
const auto target_lane_poly =
13351353
lanelet::utils::combineLaneletsShape(target_lanes).polygon2d().basicPolygon();
1354+
// to compensate for perception issue, or if object is from behind ego, and tries to overtake,
1355+
// but stop all of sudden
13361356
const auto is_overlap_with_target = [&](const LineString2d & path) {
13371357
return !boost::geometry::disjoint(path, target_lane_poly);
13381358
};

0 commit comments

Comments
 (0)