19
19
20
20
#include < memory>
21
21
#include < string>
22
+ #include < utility>
22
23
#include < vector>
23
24
namespace behavior_path_planner ::utils
24
25
{
@@ -40,8 +41,8 @@ std::vector<DrivableLanes> getNonOverlappingExpandedLanes(
40
41
void generateDrivableArea (
41
42
PathWithLaneId & path, const std::vector<DrivableLanes> & lanes,
42
43
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
43
- const double vehicle_length, const std::shared_ptr< const PlannerData> planner_data ,
44
- const bool is_driving_forward = true );
44
+ const bool enable_expanding_freespace_areas ,
45
+ const std::shared_ptr< const PlannerData> planner_data, const bool is_driving_forward = true );
45
46
46
47
void generateDrivableArea (
47
48
PathWithLaneId & path, const double vehicle_length, const double offset,
@@ -65,6 +66,11 @@ std::vector<DrivableLanes> expandLanelets(
65
66
void extractObstaclesFromDrivableArea (
66
67
PathWithLaneId & path, const std::vector<DrivableAreaInfo::Obstacle> & obstacles);
67
68
69
+ std::pair<std::vector<lanelet::ConstPoint3d>, bool > getBoundWithFreeSpaceAreas (
70
+ const std::vector<lanelet::ConstPoint3d> & original_bound,
71
+ const std::vector<lanelet::ConstPoint3d> & other_side_bound,
72
+ const std::shared_ptr<const PlannerData> planner_data, const bool is_left);
73
+
68
74
std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings (
69
75
const std::vector<lanelet::ConstPoint3d> & original_bound,
70
76
const std::shared_ptr<RouteHandler> & route_handler);
@@ -75,14 +81,22 @@ std::vector<lanelet::ConstPoint3d> getBoundWithIntersectionAreas(
75
81
const std::vector<DrivableLanes> & drivable_lanes, const bool is_left);
76
82
77
83
std::vector<geometry_msgs::msg::Point > calcBound (
78
- const std::shared_ptr<RouteHandler> route_handler,
84
+ const PathWithLaneId & path, const std::shared_ptr<const PlannerData> planner_data,
85
+ const std::vector<DrivableLanes> & drivable_lanes,
86
+ const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
87
+ const bool enable_expanding_freespace_areas, const bool is_left,
88
+ const bool is_driving_forward = true );
89
+
90
+ std::vector<geometry_msgs::msg::Point > postProcess (
91
+ const std::vector<geometry_msgs::msg::Point > & original_bound, const PathWithLaneId & path,
92
+ const std::shared_ptr<const PlannerData> planner_data,
79
93
const std::vector<DrivableLanes> & drivable_lanes,
80
94
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
81
- const bool is_left);
95
+ const bool is_left, const bool is_driving_forward = true );
82
96
83
- void makeBoundLongitudinallyMonotonic (
84
- PathWithLaneId & path, const std::shared_ptr< const PlannerData> & planner_data ,
85
- const bool is_bound_left );
97
+ std::vector<geometry_msgs::msg:: Point > makeBoundLongitudinallyMonotonic (
98
+ const std::vector<geometry_msgs::msg:: Point > & original_bound, const PathWithLaneId & path ,
99
+ const std::shared_ptr< const PlannerData> & planner_data, const bool is_left );
86
100
87
101
DrivableAreaInfo combineDrivableAreaInfo (
88
102
const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2);
0 commit comments