Skip to content

Commit

Permalink
feat(start_planner): support freespace pull out (autowarefoundation#4610
Browse files Browse the repository at this point in the history
)

feat(start_planner): add freespace pull out

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Aug 23, 2023
1 parent e0c018a commit 9c467e3
Show file tree
Hide file tree
Showing 10 changed files with 470 additions and 53 deletions.
1 change: 1 addition & 0 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ set(common_src
src/utils/start_planner/util.cpp
src/utils/start_planner/shift_pull_out.cpp
src/utils/start_planner/geometric_pull_out.cpp
src/utils/start_planner/freespace_pull_out.cpp
src/utils/path_shifter/path_shifter.cpp
src/utils/drivable_area_expansion/drivable_area_expansion.cpp
src/utils/drivable_area_expansion/map_utils.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,3 +35,39 @@
th_turn_signal_on_lateral_offset: 1.0
intersection_search_length: 30.0
length_ratio_for_turn_signal_deactivation_near_intersection: 0.5
# freespace planner
freespace_planner:
enable_freespace_planner: true
end_pose_search_start_distance: 20.0
end_pose_search_end_distance: 30.0
end_pose_search_interval: 2.0
freespace_planner_algorithm: "astar" # options: astar, rrtstar
velocity: 1.0
vehicle_shape_margin: 1.0
time_limit: 3000.0
minimum_turning_radius: 5.0
maximum_turning_radius: 5.0
turning_radius_size: 1
# search configs
search_configs:
theta_size: 144
angle_goal_range: 6.0
curve_weight: 1.2
reverse_weight: 1.0
lateral_goal_range: 0.5
longitudinal_goal_range: 2.0
# costmap configs
costmap_configs:
obstacle_threshold: 30
# -- A* search Configurations --
astar:
only_behind_solutions: false
use_back: false
distance_heuristic_weight: 1.0
# -- RRT* search Configurations --
rrtstar:
enable_update: true
use_informed_sampling: true
max_planning_time: 150.0
neighbor_radius: 8.0
margin: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp"
#include "behavior_path_planner/utils/path_shifter/path_shifter.hpp"
#include "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp"
#include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp"
#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp"
#include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp"
Expand Down Expand Up @@ -100,7 +101,9 @@ class StartPlannerModule : public SceneModuleInterface
{
}

// Condition to disable simultaneous execution
bool isBackFinished() const { return status_.back_finished; }
bool isFreespacePlanning() const { return status_.planner_type == PlannerType::FREESPACE; }

private:
std::shared_ptr<StartPlannerParameters> parameters_;
Expand All @@ -115,7 +118,15 @@ class StartPlannerModule : public SceneModuleInterface
std::unique_ptr<rclcpp::Time> last_pull_out_start_update_time_;
std::unique_ptr<Pose> last_approved_pose_;

std::shared_ptr<PullOutPlannerBase> getCurrentPlanner() const;
// generate freespace pull out paths in a separate thread
std::unique_ptr<PullOutPlannerBase> freespace_planner_;
rclcpp::TimerBase::SharedPtr freespace_planner_timer_;
rclcpp::CallbackGroup::SharedPtr freespace_planner_timer_cb_group_;
// TODO(kosuke55)
// Currently, we only do lock when updating a member of status_.
// However, we need to ensure that the value does not change when referring to it.
std::mutex mutex_;

PathWithLaneId getFullPath() const;
std::vector<Pose> searchPullOutStartPoses();

Expand All @@ -139,14 +150,20 @@ class StartPlannerModule : public SceneModuleInterface
bool hasFinishedPullOut() const;
void checkBackFinished();
bool isStopped();
bool isStuck();
bool hasFinishedCurrentPath();
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;

// check if the goal is located behind the ego in the same route segment.
bool IsGoalBehindOfEgoInSameRouteSegment() const;

// generate BehaviorPathOutput with stopping path and update status
BehaviorModuleOutput generateStopOutput();

// freespace planner
void onFreespacePlannerTimer();
bool planFreespacePath();

void setDebugData() const;

// temporary for old architecture
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
// Copyright 2023 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_
#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_

#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp"

#include <freespace_planning_algorithms/abstract_algorithm.hpp>
#include <freespace_planning_algorithms/astar_search.hpp>
#include <freespace_planning_algorithms/rrtstar.hpp>

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

#include <memory>
#include <vector>

namespace behavior_path_planner
{
using freespace_planning_algorithms::AbstractPlanningAlgorithm;
using freespace_planning_algorithms::AstarSearch;
using freespace_planning_algorithms::RRTStar;

class FreespacePullOut : public PullOutPlannerBase
{
public:
FreespacePullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
const vehicle_info_util::VehicleInfo & vehicle_info);

PlannerType getPlannerType() override { return PlannerType::FREESPACE; }

boost::optional<PullOutPath> plan(Pose start_pose, Pose end_pose) override;

protected:
std::unique_ptr<AbstractPlanningAlgorithm> planner_;
double velocity_;
bool use_back_;
};
} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ enum class PlannerType {
SHIFT = 1,
GEOMETRIC = 2,
STOP = 3,
FREESPACE = 4,
};

class PullOutPlannerBase
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,20 @@

#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp"

#include <freespace_planning_algorithms/abstract_algorithm.hpp>
#include <freespace_planning_algorithms/astar_search.hpp>
#include <freespace_planning_algorithms/rrtstar.hpp>

#include <string>
#include <vector>

namespace behavior_path_planner
{

using freespace_planning_algorithms::AstarParam;
using freespace_planning_algorithms::PlannerCommonParam;
using freespace_planning_algorithms::RRTStarParam;

struct StartPlannerParameters
{
double th_arrived_distance;
Expand Down Expand Up @@ -55,6 +64,17 @@ struct StartPlannerParameters
double backward_search_resolution;
double backward_path_update_duration;
double ignore_distance_from_lane_end;
// freespace planner
bool enable_freespace_planner;
std::string freespace_planner_algorithm;
double end_pose_search_start_distance;
double end_pose_search_end_distance;
double end_pose_search_interval;
double freespace_planner_velocity;
double vehicle_shape_margin;
PlannerCommonParam freespace_planner_common_parameters;
AstarParam astar_parameters;
RRTStarParam rrt_star_parameters;
};

} // namespace behavior_path_planner
Expand Down
65 changes: 65 additions & 0 deletions planning/behavior_path_planner/src/behavior_path_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1095,6 +1095,71 @@ StartPlannerParameters BehaviorPathPlannerNode::getStartPlannerParam()
p.backward_search_resolution = declare_parameter<double>(ns + "backward_search_resolution");
p.backward_path_update_duration = declare_parameter<double>(ns + "backward_path_update_duration");
p.ignore_distance_from_lane_end = declare_parameter<double>(ns + "ignore_distance_from_lane_end");
// freespace planner general params
{
std::string ns = "start_planner.freespace_planner.";
p.enable_freespace_planner = declare_parameter<bool>(ns + "enable_freespace_planner");
p.freespace_planner_algorithm =
declare_parameter<std::string>(ns + "freespace_planner_algorithm");
p.end_pose_search_start_distance =
declare_parameter<double>(ns + "end_pose_search_start_distance");
p.end_pose_search_end_distance = declare_parameter<double>(ns + "end_pose_search_end_distance");
p.end_pose_search_interval = declare_parameter<double>(ns + "end_pose_search_interval");
p.freespace_planner_velocity = declare_parameter<double>(ns + "velocity");
p.vehicle_shape_margin = declare_parameter<double>(ns + "vehicle_shape_margin");
p.freespace_planner_common_parameters.time_limit = declare_parameter<double>(ns + "time_limit");
p.freespace_planner_common_parameters.minimum_turning_radius =
declare_parameter<double>(ns + "minimum_turning_radius");
p.freespace_planner_common_parameters.maximum_turning_radius =
declare_parameter<double>(ns + "maximum_turning_radius");
p.freespace_planner_common_parameters.turning_radius_size =
declare_parameter<int>(ns + "turning_radius_size");
p.freespace_planner_common_parameters.maximum_turning_radius = std::max(
p.freespace_planner_common_parameters.maximum_turning_radius,
p.freespace_planner_common_parameters.minimum_turning_radius);
p.freespace_planner_common_parameters.turning_radius_size =
std::max(p.freespace_planner_common_parameters.turning_radius_size, 1);
}
// freespace planner search config
{
std::string ns = "start_planner.freespace_planner.search_configs.";
p.freespace_planner_common_parameters.theta_size = declare_parameter<int>(ns + "theta_size");
p.freespace_planner_common_parameters.angle_goal_range =
declare_parameter<double>(ns + "angle_goal_range");
p.freespace_planner_common_parameters.curve_weight =
declare_parameter<double>(ns + "curve_weight");
p.freespace_planner_common_parameters.reverse_weight =
declare_parameter<double>(ns + "reverse_weight");
p.freespace_planner_common_parameters.lateral_goal_range =
declare_parameter<double>(ns + "lateral_goal_range");
p.freespace_planner_common_parameters.longitudinal_goal_range =
declare_parameter<double>(ns + "longitudinal_goal_range");
}
// freespace planner costmap configs
{
std::string ns = "start_planner.freespace_planner.costmap_configs.";
p.freespace_planner_common_parameters.obstacle_threshold =
declare_parameter<int>(ns + "obstacle_threshold");
}
// freespace planner astar
{
std::string ns = "start_planner.freespace_planner.astar.";
p.astar_parameters.only_behind_solutions =
declare_parameter<bool>(ns + "only_behind_solutions");
p.astar_parameters.use_back = declare_parameter<bool>(ns + "use_back");
p.astar_parameters.distance_heuristic_weight =
declare_parameter<double>(ns + "distance_heuristic_weight");
}
// freespace planner rrtstar
{
std::string ns = "start_planner.freespace_planner.rrtstar.";
p.rrt_star_parameters.enable_update = declare_parameter<bool>(ns + "enable_update");
p.rrt_star_parameters.use_informed_sampling =
declare_parameter<bool>(ns + "use_informed_sampling");
p.rrt_star_parameters.max_planning_time = declare_parameter<double>(ns + "max_planning_time");
p.rrt_star_parameters.neighbor_radius = declare_parameter<double>(ns + "neighbor_radius");
p.rrt_star_parameters.margin = declare_parameter<double>(ns + "margin");
}

// validation of parameters
if (p.lateral_acceleration_sampling_num < 1) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,13 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const
if (!module->isBackFinished()) {
return false;
}
return enable_simultaneous_execution_as_candidate_module_;

// Other modules are not needed when freespace planning
if (module->isFreespacePlanning()) {
return false;
}

return enable_simultaneous_execution_as_approved_module_;
};

return std::all_of(registered_modules_.begin(), registered_modules_.end(), checker);
Expand All @@ -64,6 +70,12 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() cons
if (!module->isBackFinished()) {
return false;
}

// Other modules are not needed when freespace planning
if (module->isFreespacePlanning()) {
return false;
}

return enable_simultaneous_execution_as_candidate_module_;
};

Expand Down
Loading

0 comments on commit 9c467e3

Please sign in to comment.