@@ -73,32 +73,8 @@ void NormalLaneChange::updateLaneChangeStatus()
73
73
status_.is_ego_in_intersection =
74
74
utils::lane_change::isWithinIntersection (getRouteHandler (), current_lane, ego_footprint);
75
75
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 ();
85
77
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
- }
102
78
const auto [found_valid_path, found_safe_path] = getSafePath (status_.lane_change_path );
103
79
104
80
// Update status
@@ -180,24 +156,6 @@ bool NormalLaneChange::isStoppedAtRedTrafficLight() const
180
156
status_.lane_change_path .info .length .sum ());
181
157
}
182
158
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
-
201
159
LaneChangePath NormalLaneChange::getLaneChangePath () const
202
160
{
203
161
return status_.lane_change_path ;
@@ -1438,11 +1396,8 @@ bool NormalLaneChange::getLaneChangePaths(
1438
1396
if (status_.is_ego_in_intersection && status_.is_ego_in_turn_direction_lane ) {
1439
1397
return false ;
1440
1398
}
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 )) {
1446
1401
RCLCPP_DEBUG (logger_, " has overtaking object while ego leaves intersection" );
1447
1402
return false ;
1448
1403
}
@@ -1490,6 +1445,12 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
1490
1445
const auto target_objects = getTargetObjects (current_lanes, target_lanes);
1491
1446
debug_filtered_objects_ = target_objects;
1492
1447
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
+ }
1493
1454
CollisionCheckDebugMap debug_data;
1494
1455
const bool is_stuck = isVehicleStuck (current_lanes);
1495
1456
const auto safety_status = isLaneChangePathSafe (
@@ -1965,4 +1926,40 @@ bool NormalLaneChange::check_prepare_phase() const
1965
1926
return check_in_intersection || check_in_turns || check_in_general_lanes;
1966
1927
}
1967
1928
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
+
1968
1965
} // namespace behavior_path_planner
0 commit comments