Skip to content

Commit

Permalink
refactor(sampling_based_planner): add autoware prefix (#7348)
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem authored Jun 7, 2024
1 parent 9202dab commit c672f86
Show file tree
Hide file tree
Showing 57 changed files with 474 additions and 448 deletions.
8 changes: 4 additions & 4 deletions .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -194,10 +194,10 @@ planning/planning_validator/** [email protected] [email protected]
planning/route_handler/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/rtc_interface/** [email protected] [email protected] [email protected] [email protected]
planning/rtc_replayer/** [email protected] [email protected]
planning/sampling_based_planner/bezier_sampler/** [email protected]
planning/sampling_based_planner/frenet_planner/** [email protected]
planning/sampling_based_planner/path_sampler/** [email protected]
planning/sampling_based_planner/sampler_common/** [email protected]
planning/sampling_based_planner/autoware_bezier_sampler/** [email protected]
planning/sampling_based_planner/autoware_frenet_planner/** [email protected]
planning/sampling_based_planner/autoware_path_sampler/** [email protected]
planning/sampling_based_planner/autoware_sampler_common/** [email protected]
planning/scenario_selector/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_surround_obstacle_checker/** [email protected]
sensing/gnss_poser/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@

<group if="$(eval &quot;'$(var motion_path_planner_type)' == 'path_sampler'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="path_sampler" plugin="path_sampler::PathSampler" name="path_sampler" namespace="">
<composable_node pkg="autoware_path_sampler" plugin="autoware::path_sampler::PathSampler" name="path_sampler" namespace="">
<!-- topic remap -->
<remap from="~/input/path" to="path_smoother/path"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
Expand Down
8 changes: 4 additions & 4 deletions planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,10 @@ nav:
- 'About Path Smoother': planning/path_smoother
- 'Elastic Band': planning/path_smoother/docs/eb
- 'Sampling Based Planner':
- 'Path Sample': planning/sampling_based_planner/path_sampler
- 'Common library': planning/sampling_based_planner/sampler_common
- 'Frenet Planner': planning/sampling_based_planner/frenet_planner
- 'Bezier Sampler': planning/sampling_based_planner/bezier_sampler
- 'Path Sample': planning/sampling_based_planner/autoware_path_sampler
- 'Common library': planning/sampling_based_planner/autoware_sampler_common
- 'Frenet Planner': planning/sampling_based_planner/autoware_frenet_planner
- 'Bezier Sampler': planning/sampling_based_planner/autoware_bezier_sampler
- 'Surround Obstacle Checker':
- 'About Surround Obstacle Checker': planning/autoware_surround_obstacle_checker
- 'About Surround Obstacle Checker (Japanese)': planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja
Expand Down
4 changes: 2 additions & 2 deletions planning/behavior_path_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -38,13 +38,14 @@

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_behavior_path_planner_common</depend>
<depend>autoware_frenet_planner</depend>
<depend>autoware_path_sampler</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_planning_test_manager</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>behaviortree_cpp_v3</depend>
<depend>freespace_planning_algorithms</depend>
<depend>frenet_planner</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
<depend>lane_departure_checker</depend>
Expand All @@ -54,7 +55,6 @@
<depend>magic_enum</depend>
<depend>motion_utils</depend>
<depend>object_recognition_utils</depend>
<depend>path_sampler</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,19 +21,19 @@
#include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
#include "autoware_behavior_path_planner_common/utils/path_utils.hpp"
#include "autoware_behavior_path_planner_common/utils/utils.hpp"
#include "autoware_bezier_sampler/bezier_sampling.hpp"
#include "autoware_frenet_planner/frenet_planner.hpp"
#include "autoware_sampler_common/constraints/footprint.hpp"
#include "autoware_sampler_common/constraints/hard_constraint.hpp"
#include "autoware_sampler_common/constraints/soft_constraint.hpp"
#include "autoware_sampler_common/structures.hpp"
#include "autoware_sampler_common/transform/spline_transform.hpp"
#include "behavior_path_sampling_planner_module/sampling_planner_parameters.hpp"
#include "behavior_path_sampling_planner_module/util.hpp"
#include "bezier_sampler/bezier_sampling.hpp"
#include "frenet_planner/frenet_planner.hpp"
#include "lanelet2_extension/utility/query.hpp"
#include "lanelet2_extension/utility/utilities.hpp"
#include "motion_utils/trajectory/path_with_lane_id.hpp"
#include "rclcpp/rclcpp.hpp"
#include "sampler_common/constraints/footprint.hpp"
#include "sampler_common/constraints/hard_constraint.hpp"
#include "sampler_common/constraints/soft_constraint.hpp"
#include "sampler_common/structures.hpp"
#include "sampler_common/transform/spline_transform.hpp"
#include "tier4_autoware_utils/geometry/boost_geometry.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/math/constants.hpp"
Expand Down Expand Up @@ -73,7 +73,7 @@ struct SamplingPlannerData

struct SamplingPlannerDebugData
{
std::vector<sampler_common::Path> sampled_candidates{};
std::vector<autoware::sampler_common::Path> sampled_candidates{};
size_t previous_sampled_candidates_nb = 0UL;
std::vector<tier4_autoware_utils::Polygon2d> obstacles{};
std::vector<tier4_autoware_utils::MultiPoint2d> footprints{};
Expand Down Expand Up @@ -231,25 +231,25 @@ class SamplingPlannerModule : public SceneModuleInterface
void updateDebugMarkers();

void prepareConstraints(
sampler_common::Constraints & constraints,
autoware::sampler_common::Constraints & constraints,
const PredictedObjects::ConstSharedPtr & predicted_objects,
const std::vector<geometry_msgs::msg::Point> & left_bound,
const std::vector<geometry_msgs::msg::Point> & right_bound) const;

frenet_planner::SamplingParameters prepareSamplingParameters(
const sampler_common::State & initial_state,
const sampler_common::transform::Spline2D & path_spline,
autoware::frenet_planner::SamplingParameters prepareSamplingParameters(
const autoware::sampler_common::State & initial_state,
const autoware::sampler_common::transform::Spline2D & path_spline,
const SamplingPlannerInternalParameters & internal_params_);

PathWithLaneId convertFrenetPathToPathWithLaneID(
const frenet_planner::Path frenet_path, const lanelet::ConstLanelets & lanelets,
const autoware::frenet_planner::Path frenet_path, const lanelet::ConstLanelets & lanelets,
const double path_z);

// member
// std::shared_ptr<SamplingPlannerParameters> params_;
std::shared_ptr<SamplingPlannerInternalParameters> internal_params_;
vehicle_info_util::VehicleInfo vehicle_info_{};
std::optional<frenet_planner::Path> prev_sampling_path_ = std::nullopt;
std::optional<autoware::frenet_planner::Path> prev_sampling_path_ = std::nullopt;
// move to utils

void extendOutputDrivableArea(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__SAMPLING_PLANNER_PARAMETERS_HPP_
#define BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__SAMPLING_PLANNER_PARAMETERS_HPP_

#include "bezier_sampler/bezier_sampling.hpp"
#include "sampler_common/structures.hpp"
#include "autoware_bezier_sampler/bezier_sampling.hpp"
#include "autoware_sampler_common/structures.hpp"

#include <vector>
namespace behavior_path_planner
Expand Down Expand Up @@ -78,12 +78,12 @@ struct Sampling
std::vector<double> target_lateral_positions{};
int nb_target_lateral_positions{};
Frenet frenet;
bezier_sampler::SamplingParameters bezier{};
autoware::bezier_sampler::SamplingParameters bezier{};
};

struct SamplingPlannerInternalParameters
{
sampler_common::Constraints constraints;
autoware::sampler_common::Constraints constraints;
Sampling sampling;
Preprocessing preprocessing{};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@

#ifndef BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__UTIL_HPP_
#define BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__UTIL_HPP_
#include "sampler_common/structures.hpp"
#include "sampler_common/transform/spline_transform.hpp"
#include "autoware_sampler_common/structures.hpp"
#include "autoware_sampler_common/transform/spline_transform.hpp"

#include <tier4_autoware_utils/geometry/boost_geometry.hpp>

Expand All @@ -40,18 +40,20 @@ struct SoftConstraintsInputs
lanelet::ConstLanelets closest_lanelets_to_goal;
behavior_path_planner::PlanResult reference_path;
behavior_path_planner::PlanResult prev_module_path;
std::optional<sampler_common::Path> prev_path;
std::optional<autoware::sampler_common::Path> prev_path;
lanelet::ConstLanelets current_lanes;
};

using SoftConstraintsFunctionVector = std::vector<std::function<double(
sampler_common::Path &, const sampler_common::Constraints &, const SoftConstraintsInputs &)>>;
autoware::sampler_common::Path &, const autoware::sampler_common::Constraints &,
const SoftConstraintsInputs &)>>;

using HardConstraintsFunctionVector = std::vector<std::function<bool(
sampler_common::Path &, const sampler_common::Constraints &, const MultiPoint2d &)>>;
autoware::sampler_common::Path &, const autoware::sampler_common::Constraints &,
const MultiPoint2d &)>>;

inline std::vector<double> evaluateSoftConstraints(
sampler_common::Path & path, const sampler_common::Constraints & constraints,
autoware::sampler_common::Path & path, const autoware::sampler_common::Constraints & constraints,
const SoftConstraintsFunctionVector & soft_constraints_functions,
const SoftConstraintsInputs & input_data)
{
Expand All @@ -71,7 +73,7 @@ inline std::vector<double> evaluateSoftConstraints(
}

inline std::vector<bool> evaluateHardConstraints(
sampler_common::Path & path, const sampler_common::Constraints & constraints,
autoware::sampler_common::Path & path, const autoware::sampler_common::Constraints & constraints,
const MultiPoint2d & footprint, const HardConstraintsFunctionVector & hard_constraints)
{
std::vector<bool> constraints_results;
Expand All @@ -86,11 +88,11 @@ inline std::vector<bool> evaluateHardConstraints(
return constraints_results;
}

inline sampler_common::State getInitialState(
inline autoware::sampler_common::State getInitialState(
const geometry_msgs::msg::Pose & pose,
const sampler_common::transform::Spline2D & reference_spline)
const autoware::sampler_common::transform::Spline2D & reference_spline)
{
sampler_common::State initial_state;
autoware::sampler_common::State initial_state;
Point2d initial_state_pose{pose.position.x, pose.position.y};
const auto rpy = tier4_autoware_utils::getRPY(pose.orientation);
initial_state.pose = initial_state_pose;
Expand Down
6 changes: 3 additions & 3 deletions planning/behavior_path_sampling_planner_module/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,17 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_behavior_path_planner_common</depend>
<depend>autoware_bezier_sampler</depend>
<depend>autoware_frenet_planner</depend>
<depend>autoware_path_sampler</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_planning_test_manager</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>bezier_sampler</depend>
<depend>frenet_planner</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
<depend>lanelet2_extension</depend>
<depend>motion_utils</depend>
<depend>path_sampler</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Loading

0 comments on commit c672f86

Please sign in to comment.