Skip to content

Commit 712ab11

Browse files
feat(lane_change): check prepare phase in turn direction lanes (autowarefoundation#6726)
* feat(lane_change): check prepare phase in turn direction lanes Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Doxygen comment Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Add config Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix comments by the reviewer Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent d0c6071 commit 712ab11

File tree

7 files changed

+43
-2
lines changed

7 files changed

+43
-2
lines changed

planning/behavior_path_lane_change_module/README.md

+2-1
Original file line numberDiff line numberDiff line change
@@ -524,7 +524,8 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
524524
| Name | Unit | Type | Description | Default value |
525525
| :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
526526
| `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false |
527-
| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false |
527+
| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true |
528+
| `enable_collision_check_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true |
528529
| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 |
529530
| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false |
530531
| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false |

planning/behavior_path_lane_change_module/config/lane_change.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,7 @@
9292
enable_collision_check_for_prepare_phase:
9393
general_lanes: false
9494
intersection: true
95+
turns: true
9596
prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s]
9697
check_objects_on_current_lanes: true
9798
check_objects_on_other_lanes: true

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
@@ -109,6 +109,7 @@ struct LaneChangeParameters
109109
// collision check
110110
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
111111
bool enable_collision_check_for_prepare_phase_in_intersection{true};
112+
bool enable_collision_check_for_prepare_phase_in_turns{true};
112113
double prepare_segment_ignore_object_velocity_thresh{0.1};
113114
bool check_objects_on_current_lanes{true};
114115
bool check_objects_on_other_lanes{true};

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

+15
Original file line numberDiff line numberDiff line change
@@ -262,6 +262,21 @@ bool isWithinIntersection(
262262
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelet & lanelet,
263263
const Polygon2d & polygon);
264264

265+
/**
266+
* @brief Determines if a polygon is within lanes designated for turning.
267+
*
268+
* Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight').
269+
* It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's
270+
* area.
271+
*
272+
* @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated.
273+
* @param polygon The polygon to be checked for its presence within turn direction lanes.
274+
*
275+
* @return bool True if the polygon is within a lane designated for turning, false if it is within a
276+
* straight lane or no turn direction is specified.
277+
*/
278+
bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon);
279+
265280
/**
266281
* @brief Calculates the distance required during a lane change operation.
267282
*

planning/behavior_path_lane_change_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
7272
*node, parameter("enable_collision_check_for_prepare_phase.general_lanes"));
7373
p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter<bool>(
7474
*node, parameter("enable_collision_check_for_prepare_phase.intersection"));
75+
p.enable_collision_check_for_prepare_phase_in_turns =
76+
getOrDeclareParameter<bool>(*node, parameter("enable_collision_check_for_prepare_phase.turns"));
7577
p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter<double>(
7678
*node, parameter("prepare_segment_ignore_object_velocity_thresh"));
7779
p.check_objects_on_current_lanes =

planning/behavior_path_lane_change_module/src/scene.cpp

+9-1
Original file line numberDiff line numberDiff line change
@@ -2147,7 +2147,15 @@ bool NormalLaneChange::check_prepare_phase() const
21472147
return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint);
21482148
});
21492149

2150-
return check_in_intersection || check_in_general_lanes;
2150+
const auto check_in_turns = std::invoke([&]() {
2151+
if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns) {
2152+
return false;
2153+
}
2154+
2155+
return utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint);
2156+
});
2157+
2158+
return check_in_intersection || check_in_turns || check_in_general_lanes;
21512159
}
21522160

21532161
} // namespace behavior_path_planner

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@
3737

3838
#include <geometry_msgs/msg/detail/pose__struct.hpp>
3939

40+
#include <boost/geometry/algorithms/detail/disjoint/interface.hpp>
41+
4042
#include <lanelet2_core/LaneletMap.h>
4143
#include <lanelet2_core/geometry/LineString.h>
4244
#include <lanelet2_core/geometry/Point.h>
@@ -1222,6 +1224,17 @@ bool isWithinIntersection(
12221224
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon())));
12231225
}
12241226

1227+
bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon)
1228+
{
1229+
const std::string turn_direction = lanelet.attributeOr("turn_direction", "else");
1230+
if (turn_direction == "else" || turn_direction == "straight") {
1231+
return false;
1232+
}
1233+
1234+
return !boost::geometry::disjoint(
1235+
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet.polygon2d().basicPolygon())));
1236+
}
1237+
12251238
double calcPhaseLength(
12261239
const double velocity, const double maximum_velocity, const double acceleration,
12271240
const double duration)

0 commit comments

Comments
 (0)