Skip to content

Commit def6103

Browse files
authored
feat(goal_planner): align vehicle footprint heading parallel to parking side lane boundary (#9159)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 6e58cc2 commit def6103

File tree

7 files changed

+230
-70
lines changed

7 files changed

+230
-70
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ if(BUILD_EXAMPLES)
2727
FetchContent_Declare(
2828
matplotlibcpp17
2929
GIT_REPOSITORY https://github.com/soblin/matplotlibcpp17.git
30-
GIT_TAG main
30+
GIT_TAG master
3131
)
3232
FetchContent_MakeAvailable(matplotlibcpp17)
3333

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp

+106-10
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp"
16+
#include "autoware/behavior_path_goal_planner_module/util.hpp"
1617

1718
#include <ament_index_cpp/get_package_share_directory.hpp>
1819
#include <autoware/behavior_path_goal_planner_module/manager.hpp>
@@ -23,6 +24,7 @@
2324
#include <autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp>
2425
#include <autoware/behavior_path_planner_common/utils/path_utils.hpp>
2526
#include <autoware/route_handler/route_handler.hpp>
27+
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2628
#include <autoware_lanelet2_extension/io/autoware_osm_parser.hpp>
2729
#include <autoware_lanelet2_extension/projection/mgrs_projector.hpp>
2830
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
@@ -40,6 +42,7 @@
4042
#include <matplotlibcpp17/pyplot.h>
4143

4244
#include <chrono>
45+
#include <cmath>
4346
#include <iostream>
4447

4548
using namespace std::chrono_literals; // NOLINT
@@ -54,16 +57,58 @@ using autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDec
5457
using autoware_planning_msgs::msg::LaneletRoute;
5558
using tier4_planning_msgs::msg::PathWithLaneId;
5659

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+
5798
void plot_path_with_lane_id(
5899
matplotlibcpp17::axes::Axes & axes, const PathWithLaneId & path,
59-
const std::string & color = "red")
100+
const std::string & color = "red", const std::string & label = "")
60101
{
61102
std::vector<double> xs, ys;
62103
for (const auto & point : path.points) {
63104
xs.push_back(point.point.pose.position.x);
64105
ys.push_back(point.point.pose.position.y);
65106
}
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+
}
67112
}
68113

69114
void plot_lanelet(
@@ -97,7 +142,7 @@ void plot_lanelet(
97142
Kwargs("color"_a = "black", "linewidth"_a = linewidth, "linestyle"_a = "dashed"));
98143
}
99144

100-
std::shared_ptr<const PlannerData> instantiate_planner_data(
145+
std::shared_ptr<PlannerData> instantiate_planner_data(
101146
rclcpp::Node::SharedPtr node, const std::string & map_path, const LaneletRoute & route_msg)
102147
{
103148
lanelet::ErrorMessages errors{};
@@ -336,6 +381,51 @@ std::vector<PullOverPath> selectPullOverPaths(
336381
return selected;
337382
}
338383

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+
339429
int main(int argc, char ** argv)
340430
{
341431
using autoware::behavior_path_planner::utils::getReferencePath;
@@ -455,8 +545,8 @@ int main(int argc, char ** argv)
455545
lane_departure_checker_params.footprint_extra_margin =
456546
goal_planner_parameter.lane_departure_check_expansion_margin;
457547
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);
460550
const auto goal_candidates = goal_searcher.search(planner_data);
461551

462552
pybind11::scoped_interpreter guard{};
@@ -473,7 +563,9 @@ int main(int argc, char ** argv)
473563
plot_lanelet(ax2, lanelet);
474564
}
475565

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");
477569

478570
std::vector<PullOverPath> candidates;
479571
for (const auto & goal_candidate : goal_candidates) {
@@ -488,14 +580,18 @@ int main(int argc, char ** argv)
488580
plot_path_with_lane_id(ax1, full_path);
489581
}
490582
}
491-
const auto filtered_paths = selectPullOverPaths(
583+
[[maybe_unused]] const auto filtered_paths = selectPullOverPaths(
492584
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-
}
496585

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+
}
497591
ax1.set_aspect(Args("equal"));
498592
ax2.set_aspect(Args("equal"));
593+
ax1.legend();
594+
ax2.legend();
499595
plt.show();
500596

501597
rclcpp::shutdown();

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -364,7 +364,6 @@ class GoalPlannerModule : public SceneModuleInterface
364364
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map) const;
365365

366366
// goal seach
367-
Pose calcRefinedGoal(const Pose & goal_pose) const;
368367
GoalCandidates generateGoalCandidates() const;
369368

370369
// stop or decelerate

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp

+11-1
Original file line numberDiff line numberDiff line change
@@ -20,16 +20,17 @@
2020

2121
#include <autoware/lane_departure_checker/lane_departure_checker.hpp>
2222

23-
#include "visualization_msgs/msg/detail/marker_array__struct.hpp"
2423
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2524
#include <autoware_perception_msgs/msg/predicted_path.hpp>
2625
#include <geometry_msgs/msg/pose_stamped.hpp>
2726
#include <geometry_msgs/msg/twist_stamped.hpp>
2827
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
28+
#include <visualization_msgs/msg/marker_array.hpp>
2929

3030
#include <lanelet2_core/Forward.h>
3131

3232
#include <map>
33+
#include <memory>
3334
#include <string>
3435
#include <vector>
3536

@@ -175,6 +176,15 @@ lanelet::Points3d combineLanePoints(
175176
lanelet::Lanelet createDepartureCheckLanelet(
176177
const lanelet::ConstLanelets & pull_over_lanes, const route_handler::RouteHandler & route_handler,
177178
const bool left_side_parking);
179+
180+
std::optional<Pose> calcRefinedGoal(
181+
const Pose & goal_pose, const std::shared_ptr<RouteHandler> route_handler,
182+
const bool left_side_parking, const double vehicle_width, const double base_link2front,
183+
const double base_link2rear, const GoalPlannerParameters & parameters);
184+
185+
std::optional<Pose> calcClosestPose(
186+
const lanelet::ConstLineString3d line, const Point & query_point);
187+
178188
} // namespace autoware::behavior_path_planner::goal_planner_utils
179189

180190
#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+8-57
Original file line numberDiff line numberDiff line change
@@ -585,8 +585,14 @@ void GoalPlannerModule::updateData()
585585

586586
// update goal searcher and generate goal candidates
587587
if (thread_safe_data_.get_goal_candidates().empty()) {
588-
goal_searcher_->setReferenceGoal(
589-
calcRefinedGoal(planner_data_->route_handler->getOriginalGoalPose()));
588+
const auto refined_goal = goal_planner_utils::calcRefinedGoal(
589+
planner_data_->route_handler->getOriginalGoalPose(), planner_data_->route_handler,
590+
left_side_parking_, planner_data_->parameters.vehicle_width,
591+
planner_data_->parameters.base_link2front, planner_data_->parameters.base_link2rear,
592+
*parameters_);
593+
if (refined_goal) {
594+
goal_searcher_->setReferenceGoal(refined_goal.value());
595+
}
590596
thread_safe_data_.set_goal_candidates(generateGoalCandidates());
591597
}
592598

@@ -757,61 +763,6 @@ double GoalPlannerModule::calcModuleRequestLength() const
757763
return std::max(minimum_request_length, parameters_->pull_over_minimum_request_length);
758764
}
759765

760-
Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const
761-
{
762-
const double vehicle_width = planner_data_->parameters.vehicle_width;
763-
const double base_link2front = planner_data_->parameters.base_link2front;
764-
const double base_link2rear = planner_data_->parameters.base_link2rear;
765-
766-
const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
767-
*(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length,
768-
parameters_->forward_goal_search_length);
769-
770-
lanelet::Lanelet closest_pull_over_lanelet{};
771-
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &closest_pull_over_lanelet);
772-
773-
// calc closest center line pose
774-
Pose center_pose{};
775-
{
776-
// find position
777-
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(goal_pose.position);
778-
const auto segment = lanelet::utils::getClosestSegment(
779-
lanelet::utils::to2D(lanelet_point), closest_pull_over_lanelet.centerline());
780-
const auto p1 = segment.front().basicPoint();
781-
const auto p2 = segment.back().basicPoint();
782-
const auto direction_vector = (p2 - p1).normalized();
783-
const auto p1_to_goal = lanelet_point.basicPoint() - p1;
784-
const double s = direction_vector.dot(p1_to_goal);
785-
const auto refined_point = p1 + direction_vector * s;
786-
787-
center_pose.position.x = refined_point.x();
788-
center_pose.position.y = refined_point.y();
789-
center_pose.position.z = refined_point.z();
790-
791-
// find orientation
792-
const double yaw = std::atan2(direction_vector.y(), direction_vector.x());
793-
tf2::Quaternion tf_quat;
794-
tf_quat.setRPY(0, 0, yaw);
795-
center_pose.orientation = tf2::toMsg(tf_quat);
796-
}
797-
798-
const auto distance_from_bound = utils::getSignedDistanceFromBoundary(
799-
pull_over_lanes, vehicle_width, base_link2front, base_link2rear, center_pose,
800-
left_side_parking_);
801-
if (!distance_from_bound) {
802-
RCLCPP_ERROR(getLogger(), "fail to calculate refined goal");
803-
return goal_pose;
804-
}
805-
806-
const double sign = left_side_parking_ ? -1.0 : 1.0;
807-
const double offset_from_center_line =
808-
sign * (distance_from_bound.value() + parameters_->margin_from_boundary);
809-
810-
const auto refined_goal_pose = calcOffsetPose(center_pose, 0, -offset_from_center_line, 0);
811-
812-
return refined_goal_pose;
813-
}
814-
815766
bool GoalPlannerModule::planFreespacePath(
816767
std::shared_ptr<const PlannerData> planner_data,
817768
const std::shared_ptr<GoalSearcherBase> goal_searcher,

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

+22
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,11 @@
2020
#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp"
2121
#include "autoware_lanelet2_extension/regulatory_elements/no_parking_area.hpp"
2222
#include "autoware_lanelet2_extension/regulatory_elements/no_stopping_area.hpp"
23+
#include "autoware_lanelet2_extension/utility/query.hpp"
2324
#include "autoware_lanelet2_extension/utility/utilities.hpp"
2425

26+
#include <autoware_vehicle_info_utils/vehicle_info.hpp>
27+
2528
#include <boost/geometry/algorithms/union.hpp>
2629

2730
#include <lanelet2_core/geometry/Polygon.h>
@@ -193,8 +196,27 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr<const PlannerData> & p
193196
continue;
194197
}
195198

199+
// modify the goal_pose orientation so that vehicle footprint front heading is parallel to the
200+
// lane boundary
201+
const auto vehicle_front_midpoint =
202+
(transformed_vehicle_footprint.at(vehicle_info_utils::VehicleInfo::FrontLeftIndex) +
203+
transformed_vehicle_footprint.at(vehicle_info_utils::VehicleInfo::FrontRightIndex)) /
204+
2.0;
205+
lanelet::ConstLanelet vehicle_front_closest_lanelet;
206+
lanelet::utils::query::getClosestLanelet(
207+
pull_over_lanes, search_pose, &vehicle_front_closest_lanelet);
208+
const auto vehicle_front_pose_for_bound_opt = goal_planner_utils::calcClosestPose(
209+
left_side_parking_ ? vehicle_front_closest_lanelet.leftBound()
210+
: vehicle_front_closest_lanelet.rightBound(),
211+
autoware::universe_utils::createPoint(
212+
vehicle_front_midpoint.x(), vehicle_front_midpoint.y(), search_pose.position.z));
213+
if (!vehicle_front_pose_for_bound_opt) {
214+
continue;
215+
}
216+
const auto & vehicle_front_pose_for_bound = vehicle_front_pose_for_bound_opt.value();
196217
GoalCandidate goal_candidate{};
197218
goal_candidate.goal_pose = search_pose;
219+
goal_candidate.goal_pose.orientation = vehicle_front_pose_for_bound.orientation;
198220
goal_candidate.lateral_offset = dy;
199221
goal_candidate.id = goal_id;
200222
goal_id++;

0 commit comments

Comments
 (0)