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

chore: lc goal update #1659

Merged
merged 8 commits into from
Nov 25, 2024
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ If the target path contains a goal, modify the points of the path so that the pa
- Route is set with `allow_goal_modification=true` .
- We can set this option with [SetRoute](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/routing/srv/SetRoute.srv#L2) api service.
- We support `2D Rough Goal Pose` with the key bind `r` in RViz, but in the future there will be a panel of tools to manipulate various Route API from RViz.
- ego-vehicle is in the same lane as the goal.
- The terminal point of the current path is in the same lane sequence as the goal. If goal is on the road shoulder, then it is in the adjacent road lane sequence.

<img src="https://user-images.githubusercontent.com/39142679/237929950-989ca6c3-d48c-4bb5-81e5-e8d6a38911aa.png" width="600">

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,7 @@ struct GoalPlannerDebugData
FreespacePlannerDebugData freespace_planner{};
std::vector<Polygon2d> ego_polygons_expanded{};
lanelet::ConstLanelet expanded_pull_over_lane_between_ego{};
Polygon2d objects_extraction_polygon{};
};

struct LastApprovalData
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,12 @@ class GoalSearcher : public GoalSearcherBase
public:
GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint);

GoalCandidates search(
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const std::shared_ptr<const PlannerData> & planner_data) override;
GoalCandidates search(const std::shared_ptr<const PlannerData> & planner_data) override;
void update(
GoalCandidates & goal_candidates,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const std::shared_ptr<const PlannerData> & planner_data) const override;
const std::shared_ptr<const PlannerData> & planner_data,
const PredictedObjects & objects) const override;

// todo(kosuke55): Functions for this specific use should not be in the interface,
// so it is better to consider interface design when we implement other goal searchers.
Expand All @@ -47,7 +46,8 @@ class GoalSearcher : public GoalSearcherBase
bool isSafeGoalWithMarginScaleFactor(
const GoalCandidate & goal_candidate, const double margin_scale_factor,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const std::shared_ptr<const PlannerData> & planner_data) const override;
const std::shared_ptr<const PlannerData> & planner_data,
const PredictedObjects & objects) const override;

private:
void countObjectsToAvoid(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,12 @@ class GoalSearcherBase
const Pose & getReferenceGoal() const { return reference_goal_pose_; }

MultiPolygon2d getAreaPolygons() const { return area_polygons_; }
virtual GoalCandidates search(
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const std::shared_ptr<const PlannerData> & planner_data) = 0;
virtual GoalCandidates search(const std::shared_ptr<const PlannerData> & planner_data) = 0;
virtual void update(
[[maybe_unused]] GoalCandidates & goal_candidates,
[[maybe_unused]] const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
[[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data) const
[[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data,
[[maybe_unused]] const PredictedObjects & objects) const
{
return;
}
Expand All @@ -69,7 +68,8 @@ class GoalSearcherBase
virtual bool isSafeGoalWithMarginScaleFactor(
const GoalCandidate & goal_candidate, const double margin_scale_factor,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const std::shared_ptr<const PlannerData> & planner_data) const = 0;
const std::shared_ptr<const PlannerData> & planner_data,
const PredictedObjects & objects) const = 0;

protected:
GoalPlannerParameters parameters_{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class ShiftPullOver : public PullOverPlannerBase
std::optional<PathWithLaneId> cropPrevModulePath(
const PathWithLaneId & prev_module_path, const Pose & shift_end_pose) const;
std::optional<PullOverPath> generatePullOverPath(
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const Pose & goal_pose, const double lateral_jerk) const;
static double calcBeforeShiftedArcLength(
const PathWithLaneId & path, const double after_shifted_arc_length, const double dr);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,19 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes(
const geometry_msgs::msg::Pose ego_pose,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double outer_road_offset,
const double inner_road_offset);

/*
* @brief generate polygon to extract objects
* @param pull_over_lanes pull over lanes
* @param left_side left side or right side
* @param outer_offset outer offset from pull over lane boundary
* @param inner_offset inner offset from pull over lane boundary
* @return polygon to extract objects
*/
std::optional<Polygon2d> generateObjectExtractionPolygon(
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, const double outer_offset,
const double inner_offset);

PredictedObjects extractObjectsInExpandedPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance, double bound_offset, const PredictedObjects & objects);
Expand All @@ -82,12 +95,31 @@ bool isReferencePath(
std::optional<PathWithLaneId> cropPath(const PathWithLaneId & path, const Pose & end_pose);
PathWithLaneId cropForwardPoints(
const PathWithLaneId & path, const size_t target_seg_idx, const double forward_length);

/**
* @brief extend target_path by extend_length
* @param target_path original target path to extend
* @param reference_path reference path to extend
* @param extend_length length to extend
* @param remove_connected_zero_velocity flag to remove zero velocity if the last point of
* target_path has zero velocity
* @return extended path
*/
PathWithLaneId extendPath(
const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path,
const double extend_length);
const PathWithLaneId & target_path, const PathWithLaneId & reference_path,
const double extend_length, const bool remove_connected_zero_velocity);
/**
* @brief extend target_path to extend_pose
* @param target_path original target path to extend
* @param reference_path reference path to extend
* @param extend_pose pose to extend
* @param remove_connected_zero_velocity flag to remove zero velocity if the last point of
* target_path has zero velocity
* @return extended path
*/
PathWithLaneId extendPath(
const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path,
const Pose & extend_pose);
const PathWithLaneId & target_path, const PathWithLaneId & reference_path,
const Pose & extend_pose, const bool remove_connected_zero_velocity);

std::vector<Polygon2d> createPathFootPrints(
const PathWithLaneId & path, const double base_to_front, const double base_to_rear,
Expand All @@ -109,6 +141,23 @@ MarkerArray createLaneletPolygonMarkerArray(
MarkerArray createNumObjectsToAvoidTextsMarkerArray(
const GoalCandidates & goal_candidates, std::string && ns,
const std_msgs::msg::ColorRGBA & color);

/**
* @brief combine two points
* @param points lane points
* @param points_next next lane points
* @return combined points
*/
lanelet::Points3d combineLanePoints(
const lanelet::Points3d & points, const lanelet::Points3d & points_next);
/** @brief Create a lanelet that represents the departure check area.
* @param [in] pull_over_lanes Lanelets that the vehicle will pull over to.
* @param [in] route_handler RouteHandler object.
* @return Lanelet that goal footprints should be inside.
*/
lanelet::Lanelet createDepartureCheckLanelet(
const lanelet::ConstLanelets & pull_over_lanes, const route_handler::RouteHandler & route_handler,
const bool left_side_parking);
} // namespace autoware::behavior_path_planner::goal_planner_utils

#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,6 @@ std::optional<PullOverPath> GeometricPullOver::plan(const Pose & goal_pose)
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
const auto lanes = utils::combineLanelets(road_lanes, pull_over_lanes);

const auto & p = parallel_parking_parameters_;
const double max_steer_angle =
Expand All @@ -65,10 +64,12 @@ std::optional<PullOverPath> GeometricPullOver::plan(const Pose & goal_pose)
return {};
}

const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet(
pull_over_lanes, *planner_data_->route_handler, left_side_parking_);
const auto arc_path = planner_.getArcPath();

// check lane departure with road and shoulder lanes
if (lane_departure_checker_.checkPathWillLeaveLane(lanes, arc_path)) return {};
if (lane_departure_checker_.checkPathWillLeaveLane({departure_check_lane}, arc_path)) return {};

PullOverPath pull_over_path{};
pull_over_path.type = getPlannerType();
Expand Down
Loading
Loading