Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(avoidance): make it possible to use freespace areas in avoidance module #6001

Merged
merged 10 commits into from
Jan 29, 2024
Original file line number Diff line number Diff line change
Expand Up @@ -173,11 +173,9 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
const auto shorten_lanes =
utils::cutOverlappedLanes(data.reference_path_rough, data.drivable_lanes);
data.left_bound = toLineString3d(utils::calcBound(
planner_data_->route_handler, shorten_lanes, avoidance_parameters_->use_hatched_road_markings,
avoidance_parameters_->use_intersection_areas, true));
data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, true));
data.right_bound = toLineString3d(utils::calcBound(
planner_data_->route_handler, shorten_lanes, avoidance_parameters_->use_hatched_road_markings,
avoidance_parameters_->use_intersection_areas, false));
data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, false));

// get related objects from dynamic_objects, and then separates them as target objects and non
// target objects
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
use_opposite_lane: true
use_intersection_areas: true
use_hatched_road_markings: true
use_freespace_areas: true

# for debug
publish_debug_marker: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,9 @@ struct AvoidanceParameters
// use intersection area for avoidance
bool use_intersection_areas{false};

// use freespace area for avoidance
bool use_freespace_areas{false};

// consider avoidance return dead line
bool enable_dead_line_for_goal{false};
bool enable_dead_line_for_traffic_light{false};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
p.use_intersection_areas = getOrDeclareParameter<bool>(*node, ns + "use_intersection_areas");
p.use_hatched_road_markings =
getOrDeclareParameter<bool>(*node, ns + "use_hatched_road_markings");
p.use_freespace_areas = getOrDeclareParameter<bool>(*node, ns + "use_freespace_areas");
}

// target object
Expand Down
12 changes: 8 additions & 4 deletions planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1122 to 1125, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -235,11 +235,13 @@
auto tmp_path = getPreviousModuleOutput().path;
const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes);
data.left_bound = toLineString3d(utils::calcBound(
planner_data_->route_handler, shorten_lanes, parameters_->use_hatched_road_markings,
parameters_->use_intersection_areas, true));
getPreviousModuleOutput().path, planner_data_, shorten_lanes,
parameters_->use_hatched_road_markings, parameters_->use_intersection_areas,
parameters_->use_freespace_areas, true));
data.right_bound = toLineString3d(utils::calcBound(
planner_data_->route_handler, shorten_lanes, parameters_->use_hatched_road_markings,
parameters_->use_intersection_areas, false));
getPreviousModuleOutput().path, planner_data_, shorten_lanes,
parameters_->use_hatched_road_markings, parameters_->use_intersection_areas,
parameters_->use_freespace_areas, false));

// reference path
if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
Expand Down Expand Up @@ -938,6 +940,8 @@
// expand intersection areas
current_drivable_area_info.enable_expanding_intersection_areas =
parameters_->use_intersection_areas;
// expand freespace areas
current_drivable_area_info.enable_expanding_freespace_areas = parameters_->use_freespace_areas;

Check warning on line 944 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

AvoidanceModule::plan increases from 78 to 79 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

output.drivable_area_info = utils::combineDrivableAreaInfo(
current_drivable_area_info, getPreviousModuleOutput().drivable_area_info);
Expand Down
5 changes: 2 additions & 3 deletions planning/behavior_path_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,8 +226,7 @@ void PlannerManager::generateCombinedDrivableArea(
} else if (di.is_already_expanded) {
// for single side shift
utils::generateDrivableArea(
output.path, di.drivable_lanes, false, false, data->parameters.vehicle_length, data,
is_driving_forward);
output.path, di.drivable_lanes, false, false, false, data, is_driving_forward);
} else {
const auto shorten_lanes = utils::cutOverlappedLanes(output.path, di.drivable_lanes);

Expand All @@ -239,7 +238,7 @@ void PlannerManager::generateCombinedDrivableArea(
// for other modules where multiple modules may be launched
utils::generateDrivableArea(
output.path, expanded_lanes, di.enable_expanding_hatched_road_markings,
di.enable_expanding_intersection_areas, data->parameters.vehicle_length, data,
di.enable_expanding_intersection_areas, di.enable_expanding_freespace_areas, data,
is_driving_forward);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,7 @@ struct DrivableAreaInfo
std::vector<Obstacle> obstacles{}; // obstacles to extract from the drivable area
bool enable_expanding_hatched_road_markings{false};
bool enable_expanding_intersection_areas{false};
bool enable_expanding_freespace_areas{false};

// temporary only for pull over's freespace planning
double drivable_margin{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <memory>
#include <string>
#include <utility>
#include <vector>
namespace behavior_path_planner::utils
{
Expand All @@ -40,8 +41,8 @@ std::vector<DrivableLanes> getNonOverlappingExpandedLanes(
void generateDrivableArea(
PathWithLaneId & path, const std::vector<DrivableLanes> & lanes,
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
const double vehicle_length, const std::shared_ptr<const PlannerData> planner_data,
const bool is_driving_forward = true);
const bool enable_expanding_freespace_areas,
const std::shared_ptr<const PlannerData> planner_data, const bool is_driving_forward = true);

void generateDrivableArea(
PathWithLaneId & path, const double vehicle_length, const double offset,
Expand All @@ -62,6 +63,11 @@ std::vector<DrivableLanes> expandLanelets(
void extractObstaclesFromDrivableArea(
PathWithLaneId & path, const std::vector<DrivableAreaInfo::Obstacle> & obstacles);

std::pair<std::vector<lanelet::ConstPoint3d>, bool> getBoundWithFreeSpaceAreas(
const std::vector<lanelet::ConstPoint3d> & original_bound,
const std::vector<lanelet::ConstPoint3d> & other_side_bound,
const std::shared_ptr<const PlannerData> planner_data, const bool is_left);

std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings(
const std::vector<lanelet::ConstPoint3d> & original_bound,
const std::shared_ptr<RouteHandler> & route_handler);
Expand All @@ -72,14 +78,22 @@ std::vector<lanelet::ConstPoint3d> getBoundWithIntersectionAreas(
const std::vector<DrivableLanes> & drivable_lanes, const bool is_left);

std::vector<geometry_msgs::msg::Point> calcBound(
const std::shared_ptr<RouteHandler> route_handler,
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> planner_data,
const std::vector<DrivableLanes> & drivable_lanes,
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
const bool enable_expanding_freespace_areas, const bool is_left,
const bool is_driving_forward = true);

std::vector<geometry_msgs::msg::Point> postProcess(
const std::vector<geometry_msgs::msg::Point> & original_bound, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> planner_data,
const std::vector<DrivableLanes> & drivable_lanes,
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
const bool is_left);
const bool is_left, const bool is_driving_forward = true);

void makeBoundLongitudinallyMonotonic(
PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const bool is_bound_left);
std::vector<geometry_msgs::msg::Point> makeBoundLongitudinallyMonotonic(
const std::vector<geometry_msgs::msg::Point> & original_bound, const PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data, const bool is_left);

DrivableAreaInfo combineDrivableAreaInfo(
const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2);
Expand Down
Loading
Loading