Skip to content

Commit 1b3e0fa

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 7c78e44 commit 1b3e0fa

File tree

7 files changed

+70
-2
lines changed

7 files changed

+70
-2
lines changed

planning/behavior_path_lane_change_module/README.md

+2-1
Original file line numberDiff line numberDiff line change
@@ -412,7 +412,8 @@ The following parameters are configurable in `behavior_path_planner.param.yaml`
412412
| Name | Unit | Type | Description | Default value |
413413
| :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
414414
| `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 |
415-
| `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 |
415+
| `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 |
416+
| `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 |
416417
| `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 |
417418
| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false |
418419
| `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

+32
Original file line numberDiff line numberDiff line change
@@ -257,5 +257,37 @@ Polygon2d getEgoCurrentFootprint(
257257
bool isWithinIntersection(
258258
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelet & lanelet,
259259
const Polygon2d & polygon);
260+
261+
/**
262+
* @brief Determines if a polygon is within lanes designated for turning.
263+
*
264+
* Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight').
265+
* It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's
266+
* area.
267+
*
268+
* @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated.
269+
* @param polygon The polygon to be checked for its presence within turn direction lanes.
270+
*
271+
* @return bool True if the polygon is within a lane designated for turning, false if it is within a
272+
* straight lane or no turn direction is specified.
273+
*/
274+
bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon);
275+
276+
/**
277+
* @brief Calculates the distance required during a lane change operation.
278+
*
279+
* Used for computing prepare or lane change length based on current and maximum velocity,
280+
* acceleration, and duration, returning the lesser of accelerated distance or distance at max
281+
* velocity.
282+
*
283+
* @param velocity The current velocity of the vehicle in meters per second (m/s).
284+
* @param maximum_velocity The maximum velocity the vehicle can reach in meters per second (m/s).
285+
* @param acceleration The acceleration of the vehicle in meters per second squared (m/s^2).
286+
* @param duration The duration of the lane change in seconds (s).
287+
* @return The calculated minimum distance in meters (m).
288+
*/
289+
double calcPhaseLength(
290+
const double velocity, const double maximum_velocity, const double acceleration,
291+
const double time);
260292
} // namespace behavior_path_planner::utils::lane_change
261293
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_lane_change_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,8 @@ void LaneChangeModuleManager::init(rclcpp::Node * node)
6868
*node, parameter("enable_collision_check_for_prepare_phase.general_lanes"));
6969
p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter<bool>(
7070
*node, parameter("enable_collision_check_for_prepare_phase.intersection"));
71+
p.enable_collision_check_for_prepare_phase_in_turns =
72+
getOrDeclareParameter<bool>(*node, parameter("enable_collision_check_for_prepare_phase.turns"));
7173
p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter<double>(
7274
*node, parameter("prepare_segment_ignore_object_velocity_thresh"));
7375
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
@@ -1908,7 +1908,15 @@ bool NormalLaneChange::check_prepare_phase() const
19081908
return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint);
19091909
});
19101910

1911-
return check_in_intersection || check_in_general_lanes;
1911+
const auto check_in_turns = std::invoke([&]() {
1912+
if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns) {
1913+
return false;
1914+
}
1915+
1916+
return utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint);
1917+
});
1918+
1919+
return check_in_intersection || check_in_turns || check_in_general_lanes;
19121920
}
19131921

19141922
} // namespace behavior_path_planner

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+23
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,8 @@
3636

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

39+
#include <boost/geometry/algorithms/detail/disjoint/interface.hpp>
40+
3941
#include <lanelet2_core/LaneletMap.h>
4042
#include <lanelet2_core/geometry/LineString.h>
4143
#include <lanelet2_core/geometry/Point.h>
@@ -1196,4 +1198,25 @@ bool isWithinIntersection(
11961198
return boost::geometry::within(
11971199
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon())));
11981200
}
1201+
1202+
bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon)
1203+
{
1204+
const std::string turn_direction = lanelet.attributeOr("turn_direction", "else");
1205+
if (turn_direction == "else" || turn_direction == "straight") {
1206+
return false;
1207+
}
1208+
1209+
return !boost::geometry::disjoint(
1210+
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet.polygon2d().basicPolygon())));
1211+
}
1212+
1213+
double calcPhaseLength(
1214+
const double velocity, const double maximum_velocity, const double acceleration,
1215+
const double duration)
1216+
{
1217+
const auto length_with_acceleration =
1218+
velocity * duration + 0.5 * acceleration * std::pow(duration, 2);
1219+
const auto length_with_max_velocity = maximum_velocity * duration;
1220+
return std::min(length_with_acceleration, length_with_max_velocity);
1221+
}
11991222
} // namespace behavior_path_planner::utils::lane_change

0 commit comments

Comments
 (0)