Skip to content

Commit 7c78e44

Browse files
fix(lane_change): check prepare phase in intersection (autowarefoundation#6561)
* fix(lane_change): check prepare phase in intersection Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Add new parameter, also create function Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Rename parameters Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix spell check * fix config file Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * call the function check_prepare_phase only once Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * add parameter description in README Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * minor refactoring Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Doxygen description Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent d6aa2c7 commit 7c78e44

File tree

8 files changed

+127
-13
lines changed

8 files changed

+127
-13
lines changed

planning/behavior_path_lane_change_module/README.md

+9
Original file line numberDiff line numberDiff line change
@@ -409,6 +409,15 @@ The following parameters are configurable in `behavior_path_planner.param.yaml`
409409
| `safety_check.stuck.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true |
410410
| `safety_check.stuck.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true |
411411

412+
| Name | Unit | Type | Description | Default value |
413+
| :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
414+
| `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 |
416+
| `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 |
417+
| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false |
418+
| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false |
419+
| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true |
420+
412421
(\*1) the value must be negative.
413422

414423
### Abort lane change

planning/behavior_path_lane_change_module/config/lane_change.param.yaml

+3-1
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,9 @@
8989
stop_time: 3.0 # [s]
9090

9191
# collision check
92-
enable_prepare_segment_collision_check: true
92+
enable_collision_check_for_prepare_phase:
93+
general_lanes: false
94+
intersection: true
9395
prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s]
9496
check_objects_on_current_lanes: true
9597
check_objects_on_other_lanes: true

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -166,6 +166,8 @@ class NormalLaneChange : public LaneChangeBase
166166

167167
bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const;
168168

169+
bool check_prepare_phase() const;
170+
169171
double calcMaximumLaneChangeLength(
170172
const lanelet::ConstLanelet & current_terminal_lanelet, const double max_acc) const;
171173

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

+2-1
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,8 @@ struct LaneChangeParameters
107107
double max_longitudinal_acc{1.0};
108108

109109
// collision check
110-
bool enable_prepare_segment_collision_check{true};
110+
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
111+
bool enable_collision_check_for_prepare_phase_in_intersection{true};
111112
double prepare_segment_ignore_object_velocity_thresh{0.1};
112113
bool check_objects_on_current_lanes{true};
113114
bool check_objects_on_other_lanes{true};

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

+38-1
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "rclcpp/logger.hpp"
2424

2525
#include <route_handler/route_handler.hpp>
26+
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
2627

2728
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
2829
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
@@ -31,6 +32,7 @@
3132

3233
#include <lanelet2_core/Forward.h>
3334

35+
#include <memory>
3436
#include <string>
3537
#include <vector>
3638

@@ -185,7 +187,7 @@ std::optional<lanelet::BasicPolygon2d> createPolygon(
185187

186188
ExtendedPredictedObject transform(
187189
const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters,
188-
const LaneChangeParameters & lane_change_parameters);
190+
const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase);
189191

190192
bool isCollidedPolygonsInLanelet(
191193
const std::vector<Polygon2d> & collided_polygons, const lanelet::ConstLanelets & lanes);
@@ -220,5 +222,40 @@ lanelet::ConstLanelets generateExpandedLanelets(
220222
* @return rclcpp::Logger The logger instance configured for the specified lane change type.
221223
*/
222224
rclcpp::Logger getLogger(const std::string & type);
225+
226+
/**
227+
* @brief Computes the current footprint of the ego vehicle based on its pose and size.
228+
*
229+
* This function calculates the 2D polygon representing the current footprint of the ego vehicle.
230+
* The footprint is determined by the vehicle's pose and its dimensions, including the distance
231+
* from the base to the front and rear ends of the vehicle, as well as its width.
232+
*
233+
* @param ego_pose The current pose of the ego vehicle.
234+
* @param ego_info The structural information of the ego vehicle, such as its maximum longitudinal
235+
* offset, rear overhang, and width.
236+
*
237+
* @return Polygon2d A polygon representing the current 2D footprint of the ego vehicle.
238+
*/
239+
Polygon2d getEgoCurrentFootprint(
240+
const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info);
241+
242+
/**
243+
* @brief Checks if the given polygon is within an intersection area.
244+
*
245+
* This function evaluates whether a specified polygon is located within the bounds of an
246+
* intersection. It identifies the intersection area by checking the attributes of the provided
247+
* lanelet. If the lanelet has an attribute indicating it is part of an intersection, the function
248+
* then checks if the polygon is fully contained within this area.
249+
*
250+
* @param route_handler a shared pointer to the route_handler
251+
* @param lanelet A lanelet to check against the
252+
* intersection area.
253+
* @param polygon The polygon to check for containment within the intersection area.
254+
*
255+
* @return bool True if the polygon is within the intersection area, false otherwise.
256+
*/
257+
bool isWithinIntersection(
258+
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelet & lanelet,
259+
const Polygon2d & polygon);
223260
} // namespace behavior_path_planner::utils::lane_change
224261
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_lane_change_module/src/manager.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -64,8 +64,10 @@ void LaneChangeModuleManager::init(rclcpp::Node * node)
6464
p.max_longitudinal_acc = getOrDeclareParameter<double>(*node, parameter("max_longitudinal_acc"));
6565

6666
// collision check
67-
p.enable_prepare_segment_collision_check =
68-
getOrDeclareParameter<bool>(*node, parameter("enable_prepare_segment_collision_check"));
67+
p.enable_collision_check_for_prepare_phase_in_general_lanes = getOrDeclareParameter<bool>(
68+
*node, parameter("enable_collision_check_for_prepare_phase.general_lanes"));
69+
p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter<bool>(
70+
*node, parameter("enable_collision_check_for_prepare_phase.intersection"));
6971
p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter<double>(
7072
*node, parameter("prepare_segment_ignore_object_velocity_thresh"));
7173
p.check_objects_on_current_lanes =

planning/behavior_path_lane_change_module/src/scene.cpp

+38-5
Original file line numberDiff line numberDiff line change
@@ -802,23 +802,27 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects(
802802
target_objects.other_lane.reserve(target_obj_index.other_lane.size());
803803

804804
// objects in current lane
805+
const auto is_check_prepare_phase = check_prepare_phase();
805806
for (const auto & obj_idx : target_obj_index.current_lane) {
806807
const auto extended_object = utils::lane_change::transform(
807-
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_);
808+
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_,
809+
is_check_prepare_phase);
808810
target_objects.current_lane.push_back(extended_object);
809811
}
810812

811813
// objects in target lane
812814
for (const auto & obj_idx : target_obj_index.target_lane) {
813815
const auto extended_object = utils::lane_change::transform(
814-
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_);
816+
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_,
817+
is_check_prepare_phase);
815818
target_objects.target_lane.push_back(extended_object);
816819
}
817820

818821
// objects in other lane
819822
for (const auto & obj_idx : target_obj_index.other_lane) {
820823
const auto extended_object = utils::lane_change::transform(
821-
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_);
824+
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_,
825+
is_check_prepare_phase);
822826
target_objects.other_lane.push_back(extended_object);
823827
}
824828

@@ -878,8 +882,8 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
878882
const auto obj_velocity_norm = std::hypot(
879883
object.kinematics.initial_twist_with_covariance.twist.linear.x,
880884
object.kinematics.initial_twist_with_covariance.twist.linear.y);
881-
const auto extended_object =
882-
utils::lane_change::transform(object, common_parameters, *lane_change_parameters_);
885+
const auto extended_object = utils::lane_change::transform(
886+
object, common_parameters, *lane_change_parameters_, check_prepare_phase());
883887

884888
const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object);
885889

@@ -1878,4 +1882,33 @@ void NormalLaneChange::updateStopTime()
18781882
stop_watch_.tic("stop_time");
18791883
}
18801884

1885+
bool NormalLaneChange::check_prepare_phase() const
1886+
{
1887+
const auto & route_handler = getRouteHandler();
1888+
const auto & vehicle_info = getCommonParam().vehicle_info;
1889+
1890+
const auto check_in_general_lanes =
1891+
lane_change_parameters_->enable_collision_check_for_prepare_phase_in_general_lanes;
1892+
1893+
lanelet::ConstLanelet current_lane;
1894+
if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), &current_lane)) {
1895+
RCLCPP_DEBUG(
1896+
logger_, "Unable to get current lane. Default to %s.",
1897+
(check_in_general_lanes ? "true" : "false"));
1898+
return check_in_general_lanes;
1899+
}
1900+
1901+
const auto ego_footprint = utils::lane_change::getEgoCurrentFootprint(getEgoPose(), vehicle_info);
1902+
1903+
const auto check_in_intersection = std::invoke([&]() {
1904+
if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_intersection) {
1905+
return false;
1906+
}
1907+
1908+
return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint);
1909+
});
1910+
1911+
return check_in_intersection || check_in_general_lanes;
1912+
}
1913+
18811914
} // namespace behavior_path_planner

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+31-3
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,11 @@
3030
#include <motion_utils/trajectory/path_with_lane_id.hpp>
3131
#include <motion_utils/trajectory/trajectory.hpp>
3232
#include <rclcpp/rclcpp.hpp>
33+
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
3334
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
35+
#include <vehicle_info_util/vehicle_info.hpp>
36+
37+
#include <geometry_msgs/msg/detail/pose__struct.hpp>
3438

3539
#include <lanelet2_core/LaneletMap.h>
3640
#include <lanelet2_core/geometry/LineString.h>
@@ -1099,7 +1103,7 @@ std::optional<lanelet::BasicPolygon2d> createPolygon(
10991103
ExtendedPredictedObject transform(
11001104
const PredictedObject & object,
11011105
[[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters,
1102-
const LaneChangeParameters & lane_change_parameters)
1106+
const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase)
11031107
{
11041108
ExtendedPredictedObject extended_object;
11051109
extended_object.uuid = object.object_id;
@@ -1109,8 +1113,6 @@ ExtendedPredictedObject transform(
11091113
extended_object.shape = object.shape;
11101114

11111115
const auto & time_resolution = lane_change_parameters.prediction_time_resolution;
1112-
const auto & check_at_prepare_phase =
1113-
lane_change_parameters.enable_prepare_segment_collision_check;
11141116
const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration;
11151117
const auto & velocity_threshold =
11161118
lane_change_parameters.prepare_segment_ignore_object_velocity_thresh;
@@ -1168,4 +1170,30 @@ rclcpp::Logger getLogger(const std::string & type)
11681170
{
11691171
return rclcpp::get_logger("lane_change").get_child(type);
11701172
}
1173+
1174+
Polygon2d getEgoCurrentFootprint(
1175+
const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info)
1176+
{
1177+
const auto base_to_front = ego_info.max_longitudinal_offset_m;
1178+
const auto base_to_rear = ego_info.rear_overhang_m;
1179+
const auto width = ego_info.vehicle_width_m;
1180+
1181+
return tier4_autoware_utils::toFootprint(ego_pose, base_to_front, base_to_rear, width);
1182+
}
1183+
1184+
bool isWithinIntersection(
1185+
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelet & lanelet,
1186+
const Polygon2d & polygon)
1187+
{
1188+
const std::string id = lanelet.attributeOr("intersection_area", "else");
1189+
if (id == "else") {
1190+
return false;
1191+
}
1192+
1193+
const auto lanelet_polygon =
1194+
route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str()));
1195+
1196+
return boost::geometry::within(
1197+
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon())));
1198+
}
11711199
} // namespace behavior_path_planner::utils::lane_change

0 commit comments

Comments
 (0)