13
13
// limitations under the License.
14
14
15
15
#include " autoware/behavior_path_goal_planner_module/goal_searcher.hpp"
16
+ #include " autoware/behavior_path_goal_planner_module/util.hpp"
16
17
17
18
#include < ament_index_cpp/get_package_share_directory.hpp>
18
19
#include < autoware/behavior_path_goal_planner_module/manager.hpp>
23
24
#include < autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp>
24
25
#include < autoware/behavior_path_planner_common/utils/path_utils.hpp>
25
26
#include < autoware/route_handler/route_handler.hpp>
27
+ #include < autoware/universe_utils/geometry/boost_geometry.hpp>
26
28
#include < autoware_lanelet2_extension/io/autoware_osm_parser.hpp>
27
29
#include < autoware_lanelet2_extension/projection/mgrs_projector.hpp>
28
30
#include < autoware_lanelet2_extension/utility/message_conversion.hpp>
40
42
#include < matplotlibcpp17/pyplot.h>
41
43
42
44
#include < chrono>
45
+ #include < cmath>
43
46
#include < iostream>
44
47
45
48
using namespace std ::chrono_literals; // NOLINT
@@ -54,16 +57,58 @@ using autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDec
54
57
using autoware_planning_msgs::msg::LaneletRoute;
55
58
using tier4_planning_msgs::msg::PathWithLaneId;
56
59
60
+ void plot_footprint (
61
+ matplotlibcpp17::axes::Axes & axes, const autoware::universe_utils::LinearRing2d & footprint,
62
+ const std::string & color = " blue" )
63
+ {
64
+ std::vector<double > xs, ys;
65
+ for (const auto & pt : footprint) {
66
+ xs.push_back (pt.x ());
67
+ ys.push_back (pt.y ());
68
+ }
69
+ xs.push_back (xs.front ());
70
+ ys.push_back (ys.front ());
71
+ axes.plot (Args (xs, ys), Kwargs (" color" _a = color, " linestyle" _a = " dotted" ));
72
+ }
73
+
74
+ void plot_goal_candidates (
75
+ matplotlibcpp17::axes::Axes & axes, const GoalCandidates & goals,
76
+ const autoware::universe_utils::LinearRing2d & local_footprint,
77
+ const std::string & color = " green" )
78
+ {
79
+ std::vector<double > xs, ys;
80
+ std::vector<double > yaw_cos, yaw_sin;
81
+ for (const auto & goal : goals) {
82
+ const auto goal_footprint =
83
+ transformVector (local_footprint, autoware::universe_utils::pose2transform (goal.goal_pose ));
84
+ plot_footprint (axes, goal_footprint);
85
+ xs.push_back (goal.goal_pose .position .x );
86
+ ys.push_back (goal.goal_pose .position .y );
87
+ axes.text (Args (xs.back (), ys.back (), std::to_string (goal.id )));
88
+ const double yaw = autoware::universe_utils::getRPY (goal.goal_pose ).z ;
89
+ yaw_cos.push_back (std::cos (yaw));
90
+ yaw_sin.push_back (std::sin (yaw));
91
+ }
92
+ axes.scatter (Args (xs, ys), Kwargs (" color" _a = color));
93
+ axes.quiver (
94
+ Args (xs, ys, yaw_cos, yaw_sin),
95
+ Kwargs (" angles" _a = " xy" , " scale_units" _a = " xy" , " scale" _a = 1.0 ));
96
+ }
97
+
57
98
void plot_path_with_lane_id (
58
99
matplotlibcpp17::axes::Axes & axes, const PathWithLaneId & path,
59
- const std::string & color = " red" )
100
+ const std::string & color = " red" , const std::string & label = " " )
60
101
{
61
102
std::vector<double > xs, ys;
62
103
for (const auto & point : path.points ) {
63
104
xs.push_back (point.point .pose .position .x );
64
105
ys.push_back (point.point .pose .position .y );
65
106
}
66
- axes.plot (Args (xs, ys), Kwargs (" color" _a = color, " linewidth" _a = 1.0 ));
107
+ if (label == " " ) {
108
+ axes.plot (Args (xs, ys), Kwargs (" color" _a = color, " linewidth" _a = 1.0 ));
109
+ } else {
110
+ axes.plot (Args (xs, ys), Kwargs (" color" _a = color, " linewidth" _a = 1.0 , " label" _a = label));
111
+ }
67
112
}
68
113
69
114
void plot_lanelet (
@@ -97,7 +142,7 @@ void plot_lanelet(
97
142
Kwargs (" color" _a = " black" , " linewidth" _a = linewidth, " linestyle" _a = " dashed" ));
98
143
}
99
144
100
- std::shared_ptr<const PlannerData> instantiate_planner_data (
145
+ std::shared_ptr<PlannerData> instantiate_planner_data (
101
146
rclcpp::Node::SharedPtr node, const std::string & map_path, const LaneletRoute & route_msg)
102
147
{
103
148
lanelet::ErrorMessages errors{};
@@ -336,6 +381,51 @@ std::vector<PullOverPath> selectPullOverPaths(
336
381
return selected;
337
382
}
338
383
384
+ std::optional<PathWithLaneId> calculate_centerline_path (
385
+ const geometry_msgs::msg::Pose & original_goal_pose,
386
+ const std::shared_ptr<PlannerData> planner_data, const GoalPlannerParameters & parameters)
387
+ {
388
+ const auto refined_goal_opt =
389
+ autoware::behavior_path_planner::goal_planner_utils::calcRefinedGoal (
390
+ original_goal_pose, planner_data->route_handler , true ,
391
+ planner_data->parameters .vehicle_length , planner_data->parameters .base_link2front ,
392
+ planner_data->parameters .base_link2front , parameters);
393
+ if (!refined_goal_opt) {
394
+ return std::nullopt;
395
+ }
396
+ const auto & refined_goal = refined_goal_opt.value ();
397
+
398
+ const auto & route_handler = planner_data->route_handler ;
399
+ const double forward_length = parameters.forward_goal_search_length ;
400
+ const double backward_length = parameters.backward_goal_search_length ;
401
+ const bool use_bus_stop_area = parameters.bus_stop_area .use_bus_stop_area ;
402
+ /*
403
+ const double margin_from_boundary = parameters.margin_from_boundary;
404
+ const double lateral_offset_interval = use_bus_stop_area
405
+ ? parameters.bus_stop_area.lateral_offset_interval
406
+ : parameters.lateral_offset_interval;
407
+ const double max_lateral_offset = parameters.max_lateral_offset;
408
+ const double ignore_distance_from_lane_start = parameters.ignore_distance_from_lane_start;
409
+ */
410
+
411
+ const auto pull_over_lanes =
412
+ autoware::behavior_path_planner::goal_planner_utils::getPullOverLanes (
413
+ *route_handler, true , parameters.backward_goal_search_length ,
414
+ parameters.forward_goal_search_length );
415
+ const auto departure_check_lane =
416
+ autoware::behavior_path_planner::goal_planner_utils::createDepartureCheckLanelet (
417
+ pull_over_lanes, *route_handler, true );
418
+ const auto goal_arc_coords = lanelet::utils::getArcCoordinates (pull_over_lanes, refined_goal);
419
+ const double s_start = std::max (0.0 , goal_arc_coords.length - backward_length);
420
+ const double s_end = goal_arc_coords.length + forward_length;
421
+ const double longitudinal_interval = use_bus_stop_area
422
+ ? parameters.bus_stop_area .goal_search_interval
423
+ : parameters.goal_search_interval ;
424
+ auto center_line_path = autoware::behavior_path_planner::utils::resamplePathWithSpline (
425
+ route_handler->getCenterLinePath (pull_over_lanes, s_start, s_end), longitudinal_interval);
426
+ return center_line_path;
427
+ }
428
+
339
429
int main (int argc, char ** argv)
340
430
{
341
431
using autoware::behavior_path_planner::utils::getReferencePath;
@@ -455,8 +545,8 @@ int main(int argc, char ** argv)
455
545
lane_departure_checker_params.footprint_extra_margin =
456
546
goal_planner_parameter.lane_departure_check_expansion_margin ;
457
547
lane_departure_checker.setParam (lane_departure_checker_params);
458
- autoware::behavior_path_planner::GoalSearcher goal_searcher (
459
- goal_planner_parameter, vehicle_info. createFootprint () );
548
+ const auto footprint = vehicle_info. createFootprint ();
549
+ autoware::behavior_path_planner::GoalSearcher goal_searcher ( goal_planner_parameter, footprint );
460
550
const auto goal_candidates = goal_searcher.search (planner_data);
461
551
462
552
pybind11::scoped_interpreter guard{};
@@ -473,7 +563,9 @@ int main(int argc, char ** argv)
473
563
plot_lanelet (ax2, lanelet);
474
564
}
475
565
476
- plot_path_with_lane_id (ax1, reference_path.path , " green" );
566
+ plot_goal_candidates (ax1, goal_candidates, footprint);
567
+
568
+ plot_path_with_lane_id (ax2, reference_path.path , " green" , " reference_path" );
477
569
478
570
std::vector<PullOverPath> candidates;
479
571
for (const auto & goal_candidate : goal_candidates) {
@@ -488,14 +580,18 @@ int main(int argc, char ** argv)
488
580
plot_path_with_lane_id (ax1, full_path);
489
581
}
490
582
}
491
- const auto filtered_paths = selectPullOverPaths (
583
+ [[maybe_unused]] const auto filtered_paths = selectPullOverPaths (
492
584
candidates, goal_candidates, planner_data, goal_planner_parameter, reference_path);
493
- for (const auto & filtered_path : filtered_paths) {
494
- plot_path_with_lane_id (ax2, filtered_path.full_path (), " blue" );
495
- }
496
585
586
+ const auto centerline_path =
587
+ calculate_centerline_path (route_msg.goal_pose , planner_data, goal_planner_parameter);
588
+ if (centerline_path) {
589
+ plot_path_with_lane_id (ax2, centerline_path.value (), " red" , " centerline_path" );
590
+ }
497
591
ax1.set_aspect (Args (" equal" ));
498
592
ax2.set_aspect (Args (" equal" ));
593
+ ax1.legend ();
594
+ ax2.legend ();
499
595
plt.show ();
500
596
501
597
rclcpp::shutdown ();
0 commit comments