Skip to content

Commit 34f4171

Browse files
separate target lane leading objects based on behavior (RT1-8532)
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent f112f65 commit 34f4171

File tree

11 files changed

+237
-275
lines changed

11 files changed

+237
-275
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -128,8 +128,7 @@ class NormalLaneChange : public LaneChangeBase
128128

129129
void filterOncomingObjects(PredictedObjects & objects) const;
130130

131-
FilteredByLanesObjects filterObjectsByLanelets(
132-
const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path) const;
131+
FilteredByLanesExtendedObjects filterObjectsByLanelets(const PredictedObjects & objects) const;
133132

134133
bool get_prepare_segment(
135134
PathWithLaneId & prepare_segment, const double prepare_length) const override;

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp

+14-17
Original file line numberDiff line numberDiff line change
@@ -262,23 +262,21 @@ struct Info
262262
}
263263
};
264264

265-
template <typename Object>
265+
struct TargetLaneLeadingObjects
266+
{
267+
ExtendedPredictedObjects moving;
268+
ExtendedPredictedObjects stopped;
269+
ExtendedPredictedObjects expanded;
270+
271+
[[nodiscard]] size_t size() const { return moving.size() + stopped.size() + expanded.size(); }
272+
};
273+
266274
struct LanesObjects
267275
{
268-
Object current_lane{};
269-
Object target_lane_leading{};
270-
Object target_lane_trailing{};
271-
Object other_lane{};
272-
273-
LanesObjects() = default;
274-
LanesObjects(
275-
Object current_lane, Object target_lane_leading, Object target_lane_trailing, Object other_lane)
276-
: current_lane(std::move(current_lane)),
277-
target_lane_leading(std::move(target_lane_leading)),
278-
target_lane_trailing(std::move(target_lane_trailing)),
279-
other_lane(std::move(other_lane))
280-
{
281-
}
276+
ExtendedPredictedObjects others;
277+
ExtendedPredictedObjects current_lane;
278+
ExtendedPredictedObjects target_lane_trailing;
279+
TargetLaneLeadingObjects target_lane_leading;
282280
};
283281

284282
struct TargetObjects
@@ -418,8 +416,7 @@ using LaneChangeStates = lane_change::States;
418416
using LaneChangePhaseInfo = lane_change::PhaseInfo;
419417
using LaneChangePhaseMetrics = lane_change::PhaseMetrics;
420418
using LaneChangeInfo = lane_change::Info;
421-
using FilteredByLanesObjects = lane_change::LanesObjects<std::vector<PredictedObject>>;
422-
using FilteredByLanesExtendedObjects = lane_change::LanesObjects<ExtendedPredictedObjects>;
419+
using FilteredByLanesExtendedObjects = lane_change::LanesObjects;
423420
using LateralAccelerationMap = lane_change::LateralAccelerationMap;
424421
} // namespace autoware::behavior_path_planner
425422

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -55,9 +55,11 @@ struct Debug
5555
collision_check_objects.clear();
5656
collision_check_objects_after_approval.clear();
5757
filtered_objects.current_lane.clear();
58-
filtered_objects.target_lane_leading.clear();
5958
filtered_objects.target_lane_trailing.clear();
60-
filtered_objects.other_lane.clear();
59+
filtered_objects.target_lane_leading.moving.clear();
60+
filtered_objects.target_lane_leading.stopped.clear();
61+
filtered_objects.target_lane_leading.expanded.clear();
62+
filtered_objects.others.clear();
6163
execution_area.points.clear();
6264
current_lanes.clear();
6365
target_lanes.clear();

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp

+12-9
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ using behavior_path_planner::lane_change::CommonDataPtr;
5454
using behavior_path_planner::lane_change::LanesPolygon;
5555
using behavior_path_planner::lane_change::ModuleType;
5656
using behavior_path_planner::lane_change::PathSafetyStatus;
57+
using behavior_path_planner::lane_change::TargetLaneLeadingObjects;
5758
using geometry_msgs::msg::Point;
5859
using geometry_msgs::msg::Pose;
5960
using geometry_msgs::msg::Twist;
@@ -144,8 +145,7 @@ lanelet::BasicPolygon2d create_polygon(
144145
const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist);
145146

146147
ExtendedPredictedObject transform(
147-
const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters,
148-
const LaneChangeParameters & lane_change_parameters);
148+
const PredictedObject & object, const LaneChangeParameters & lane_change_parameters);
149149

150150
bool is_collided_polygons_in_lanelet(
151151
const std::vector<Polygon2d> & collided_polygons, const lanelet::BasicPolygon2d & lanes_polygon);
@@ -240,17 +240,14 @@ bool is_same_lane_with_prev_iteration(
240240

241241
bool is_ahead_of_ego(
242242
const CommonDataPtr & common_data_ptr, const PathWithLaneId & path,
243-
const PredictedObject & object);
243+
const ExtendedPredictedObject & object);
244244

245245
bool is_before_terminal(
246246
const CommonDataPtr & common_data_ptr, const PathWithLaneId & path,
247-
const PredictedObject & object);
247+
const ExtendedPredictedObject & object);
248248

249249
double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose);
250250

251-
ExtendedPredictedObjects transform_to_extended_objects(
252-
const CommonDataPtr & common_data_ptr, const std::vector<PredictedObject> & objects);
253-
254251
double get_distance_to_next_regulatory_element(
255252
const CommonDataPtr & common_data_ptr, const bool ignore_crosswalk = false,
256253
const bool ignore_intersection = false);
@@ -294,8 +291,8 @@ double get_min_dist_to_current_lanes_obj(
294291
* otherwise, false.
295292
*/
296293
bool has_blocking_target_object(
297-
const CommonDataPtr & common_data_ptr, const FilteredByLanesExtendedObjects & filtered_objects,
298-
const double stop_arc_length, const PathWithLaneId & path);
294+
const TargetLaneLeadingObjects & target_leading_objects, const double stop_arc_length,
295+
const PathWithLaneId & path);
299296

300297
/**
301298
* @brief Checks if the ego vehicle has passed any turn direction within an intersection.
@@ -342,5 +339,11 @@ std::vector<LineString2d> get_line_string_paths(const ExtendedPredictedObject &
342339
*/
343340
bool has_overtaking_turn_lane_object(
344341
const CommonDataPtr & common_data_ptr, const ExtendedPredictedObjects & trailing_objects);
342+
343+
void filter_target_lane_objects(
344+
const CommonDataPtr & common_data_ptr, const ExtendedPredictedObject & object,
345+
const double dist_ego_to_current_lanes_center, const bool ahead_of_ego,
346+
const bool before_terminal, TargetLaneLeadingObjects & leading_objects,
347+
ExtendedPredictedObjects & trailing_objects);
345348
} // namespace autoware::behavior_path_planner::utils::lane_change
346349
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
<depend>autoware_rtc_interface</depend>
2828
<depend>autoware_universe_utils</depend>
2929
<depend>pluginlib</depend>
30+
<depend>range-v3</depend>
3031
<depend>rclcpp</depend>
3132
<depend>tier4_planning_msgs</depend>
3233
<depend>visualization_msgs</depend>

0 commit comments

Comments
 (0)