Skip to content

Commit 98f9724

Browse files
zulfaqar-azmi-t4saka1-s
authored andcommitted
fix(lane_change): enable cancel when ego in turn direction lane (RT0-33893) (#1594)
* yield at intersection by making the check conservative Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * make code of similar to main branch Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix build error Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix logic Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * update README Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * change variable name Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 3cacd75 commit 98f9724

File tree

10 files changed

+164
-0
lines changed

10 files changed

+164
-0
lines changed

planning/behavior_path_lane_change_module/README.md

+1
Original file line numberDiff line numberDiff line change
@@ -341,6 +341,7 @@ The following parameters are configurable in `lane_change.param.yaml`.
341341
| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 |
342342
| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 |
343343
| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 |
344+
| `backward_length_from_intersection` | [m] | double | Distance threshold from the last intersection to invalidate or cancel the lane change path | 5.0 |
344345
| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 |
345346
| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 |
346347
| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 |

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
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,9 @@ class NormalLaneChange : public LaneChangeBase
186186

187187
double getStopTime() const { return stop_time_; }
188188

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

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

+1
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,7 @@ struct LaneChangeParameters
9393
// lane change parameters
9494
double backward_length_buffer_for_end_of_lane;
9595
double backward_length_buffer_for_blocking_object;
96+
double backward_length_from_intersection{5.0};
9697
double lane_changing_lateral_jerk{0.5};
9798
double minimum_lane_changing_velocity{5.6};
9899
double lane_change_prepare_duration{4.0};

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

+5
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
2323

24+
#include <limits>
2425
#include <vector>
2526

2627
namespace behavior_path_planner
@@ -42,11 +43,15 @@ struct LaneChangeStatus
4243
LaneChangePath lane_change_path{};
4344
lanelet::ConstLanelets current_lanes{};
4445
lanelet::ConstLanelets target_lanes{};
46+
lanelet::ConstLanelet ego_lane{};
4547
std::vector<lanelet::Id> lane_follow_lane_ids{};
4648
std::vector<lanelet::Id> lane_change_lane_ids{};
4749
bool is_safe{false};
4850
bool is_valid_path{true};
51+
bool is_ego_in_turn_direction_lane{false};
52+
bool is_ego_in_intersection{false};
4953
double start_distance{0.0};
54+
double dist_from_prev_intersection{std::numeric_limits<double>::max()};
5055
};
5156

5257
} // namespace behavior_path_planner

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

+10
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@ using autoware_auto_perception_msgs::msg::PredictedObjects;
4343
using autoware_auto_perception_msgs::msg::PredictedPath;
4444
using autoware_auto_planning_msgs::msg::PathWithLaneId;
4545
using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject;
46+
using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects;
4647
using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped;
4748
using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped;
4849
using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon;
@@ -338,5 +339,14 @@ bool has_blocking_target_object(
338339
const lanelet::ConstLanelets & target_lanes, const LaneChangeTargetObjects & filtered_objects,
339340
const LaneChangeParameters & lc_param, const double stop_arc_length, const Pose & ego_pose,
340341
const PathWithLaneId & path);
342+
343+
bool has_passed_intersection_turn_direction(
344+
const LaneChangeParameters & lc_param, const LaneChangeStatus & status);
345+
346+
std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject & object);
347+
348+
bool has_overtaking_turn_lane_object(
349+
const LaneChangeStatus & status, const LaneChangeParameters & lc_param,
350+
const ExtendedPredictedObjects & trailing_objects);
341351
} // namespace behavior_path_planner::utils::lane_change
342352
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_lane_change_module/src/interface.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,7 @@ ModuleStatus LaneChangeInterface::updateState()
120120
module_type_->evaluateApprovedPathWithUnsafeHysteresis(module_type_->isApprovedPathSafe());
121121

122122
setObjectDebugVisualization();
123+
123124
if (is_safe) {
124125
log_warn_throttled("Lane change path is safe.");
125126
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

+72
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,27 @@ NormalLaneChange::NormalLaneChange(
5454
void NormalLaneChange::updateLaneChangeStatus()
5555
{
5656
updateStopTime();
57+
status_.current_lanes = getCurrentLanes();
58+
if (status_.current_lanes.empty()) {
59+
return;
60+
}
61+
62+
lanelet::ConstLanelet current_lane;
63+
if (!getRouteHandler()->getClosestLaneletWithinRoute(getEgoPose(), &current_lane)) {
64+
RCLCPP_DEBUG(logger_, "ego's current lane not in route");
65+
return;
66+
}
67+
status_.ego_lane = current_lane;
68+
69+
const auto ego_footprint =
70+
utils::lane_change::getEgoCurrentFootprint(getEgoPose(), getCommonParam().vehicle_info);
71+
status_.is_ego_in_turn_direction_lane =
72+
utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint);
73+
status_.is_ego_in_intersection =
74+
utils::lane_change::isWithinIntersection(getRouteHandler(), current_lane, ego_footprint);
75+
76+
update_dist_from_intersection();
77+
5778
const auto [found_valid_path, found_safe_path] = getSafePath(status_.lane_change_path);
5879

5980
// Update status
@@ -1372,6 +1393,15 @@ bool NormalLaneChange::getLaneChangePaths(
13721393
}
13731394
candidate_paths->push_back(*candidate_path);
13741395

1396+
if (status_.is_ego_in_intersection && status_.is_ego_in_turn_direction_lane) {
1397+
return false;
1398+
}
1399+
if (utils::lane_change::has_overtaking_turn_lane_object(
1400+
status_, *lane_change_parameters_, target_objects.target_lane)) {
1401+
RCLCPP_DEBUG(logger_, "has overtaking object while ego leaves intersection");
1402+
return false;
1403+
}
1404+
13751405
std::vector<ExtendedPredictedObject> filtered_objects =
13761406
filterObjectsInTargetLane(target_objects, target_lanes);
13771407
if (
@@ -1415,6 +1445,12 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
14151445
const auto target_objects = getTargetObjects(current_lanes, target_lanes);
14161446
debug_filtered_objects_ = target_objects;
14171447

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+
}
14181454
CollisionCheckDebugMap debug_data;
14191455
const bool is_stuck = isVehicleStuck(current_lanes);
14201456
const auto safety_status = isLaneChangePathSafe(
@@ -1890,4 +1926,40 @@ bool NormalLaneChange::check_prepare_phase() const
18901926
return check_in_intersection || check_in_turns || check_in_general_lanes;
18911927
}
18921928

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+
18931965
} // namespace behavior_path_planner

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+67
Original file line numberDiff line numberDiff line change
@@ -1305,4 +1305,71 @@ bool has_blocking_target_object(
13051305
return (arc_length_to_target_lane_obj - width_margin) >= stop_arc_length;
13061306
});
13071307
}
1308+
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+
1319+
std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject & object)
1320+
{
1321+
const auto transform = [](const auto & predicted_path) -> LineString2d {
1322+
LineString2d line_string;
1323+
const auto & path = predicted_path.path;
1324+
line_string.reserve(path.size());
1325+
for (const auto & path_point : path) {
1326+
const auto point = tier4_autoware_utils::fromMsg(path_point.pose.position).to_2d();
1327+
line_string.push_back(point);
1328+
}
1329+
1330+
return line_string;
1331+
};
1332+
1333+
const auto paths = object.predicted_paths;
1334+
std::vector<LineString2d> line_strings;
1335+
std::transform(paths.begin(), paths.end(), std::back_inserter(line_strings), transform);
1336+
1337+
return line_strings;
1338+
}
1339+
1340+
bool has_overtaking_turn_lane_object(
1341+
const LaneChangeStatus & status, const LaneChangeParameters & lc_param,
1342+
const ExtendedPredictedObjects & trailing_objects)
1343+
{
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 false;
1347+
}
1348+
1349+
const auto & target_lanes = status.target_lanes;
1350+
const auto & ego_current_lane = status.ego_lane;
1351+
1352+
const auto target_lane_poly =
1353+
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
1356+
const auto is_overlap_with_target = [&](const LineString2d & path) {
1357+
return !boost::geometry::disjoint(path, target_lane_poly);
1358+
};
1359+
1360+
return std::any_of(
1361+
trailing_objects.begin(), trailing_objects.end(), [&](const ExtendedPredictedObject & object) {
1362+
lanelet::ConstLanelet obj_lane;
1363+
const auto obj_poly =
1364+
tier4_autoware_utils::toPolygon2d(object.initial_pose.pose, object.shape);
1365+
if (!boost::geometry::disjoint(
1366+
obj_poly, utils::toPolygon2d(
1367+
lanelet::utils::to2D(ego_current_lane.polygon2d().basicPolygon())))) {
1368+
return true;
1369+
}
1370+
1371+
const auto paths = get_line_string_paths(object);
1372+
return std::any_of(paths.begin(), paths.end(), is_overlap_with_target);
1373+
});
1374+
}
13081375
} // namespace behavior_path_planner::utils::lane_change

0 commit comments

Comments
 (0)