Skip to content

Commit

Permalink
feat(behavior_path_planner): update pull out (tier4#1438)
Browse files Browse the repository at this point in the history
* feat(behavior_path_planner): update pull out

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* refactor(behavior_path_planner): rename pull_out params

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* update from review

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* use debug_data

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* enable back

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* move PlannerType

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* fix debug marker

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* add seach priority

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* change before_pull_out_straight_distance to 0.0

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 authored and boyali committed Oct 3, 2022
1 parent b7fabcd commit 1235738
Show file tree
Hide file tree
Showing 24 changed files with 1,172 additions and 1,210 deletions.
Original file line number Diff line number Diff line change
@@ -1,25 +1,30 @@
/**:
ros__parameters:
pull_out:
min_stop_distance: 2.0
stop_time: 0.0
hysteresis_buffer_distance: 1.0
pull_out_prepare_duration: 4.0
pull_out_duration: 2.0
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
collision_check_margin: 1.0
pull_out_finish_judge_buffer: 1.0
minimum_pull_out_velocity: 2.0
prediction_duration: 30.0
prediction_time_resolution: 0.5
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
enable_collision_check_at_prepare_phase: false
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false
use_dynamic_object: true
enable_blocked_by_obstacle: false
pull_out_search_distance: 30.0
before_pull_out_straight_distance: 5.0
after_pull_out_straight_distance: 5.0
# shift pull out
enable_shift_pull_out: true
shift_pull_out_velocity: 2.0
pull_out_sampling_num: 4
before_pull_out_straight_distance: 0.0
minimum_shift_pull_out_distance: 20.0
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
# geometric pull out
enable_geometric_pull_out: true
geometric_pull_out_velocity: 1.0
arc_path_interval: 1.0
lane_departure_margin: 0.2
backward_velocity: -1.0
pull_out_max_steer_angle: 0.26 # 15deg
# search start pose backward
enable_back: true
search_priority: "efficient_path" # "efficient_path" or "short_back_distance"
max_back_distance: 15.0
backward_search_resolution: 2.0
backward_path_update_duration: 3.0
2 changes: 2 additions & 0 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ ament_auto_add_library(behavior_path_planner_node SHARED
src/scene_module/pull_over/util.cpp
src/scene_module/pull_out/pull_out_module.cpp
src/scene_module/pull_out/util.cpp
src/scene_module/pull_out/shift_pull_out.cpp
src/scene_module/pull_out/geometric_pull_out.cpp
src/scene_module/utils/geometric_parallel_parking.cpp
src/scene_module/utils/occupancy_grid_based_collision_detector.cpp
src/scene_module/utils/path_shifter.cpp
Expand Down
42 changes: 23 additions & 19 deletions planning/behavior_path_planner/config/pull_out/pull_out.param.yaml
Original file line number Diff line number Diff line change
@@ -1,26 +1,30 @@
/**:
ros__parameters:
pull_out:
min_stop_distance: 2.0
stop_time: 0.0
hysteresis_buffer_distance: 1.0
pull_out_prepare_duration: 4.0
pull_out_duration: 2.0
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
collision_check_margin: 1.0
pull_out_finish_judge_buffer: 1.0
minimum_pull_out_velocity: 2.0
prediction_duration: 30.0
prediction_time_resolution: 0.5
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
enable_abort_pull_out: false
enable_collision_check_at_prepare_phase: false
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false
use_dynamic_object: false
enable_blocked_by_obstacle: false
pull_out_search_distance: 30.0
before_pull_out_straight_distance: 5.0
after_pull_out_straight_distance: 5.0
# shift pull out
enable_shift_pull_out: true
shift_pull_out_velocity: 2.0
pull_out_sampling_num: 4
before_pull_out_straight_distance: 0.0
minimum_shift_pull_out_distance: 20.0
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
# geometric pull out
enable_geometric_pull_out: true
geometric_pull_out_velocity: 1.0
arc_path_interval: 1.0
lane_departure_margin: 0.2
backward_velocity: -1.0
pull_out_max_steer_angle: 0.26 # 15deg
# search start pose backward
enable_back: true
search_priority: "efficient_path" # "efficient_path" or "short_back_distance"
max_back_distance: 15.0
backward_search_resolution: 2.0
backward_path_update_duration: 3.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// Copyright 2022 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__SCENE_MODULE__PULL_OUT__GEOMETRIC_PULL_OUT_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__GEOMETRIC_PULL_OUT_HPP_

#include "behavior_path_planner/scene_module/pull_out/pull_out_path.hpp"
#include "behavior_path_planner/scene_module/pull_out/pull_out_planner_base.hpp"
#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

namespace behavior_path_planner
{
class GeometricPullOut : public PullOutPlannerBase
{
public:
explicit GeometricPullOut(
rclcpp::Node & node, const PullOutParameters & parameters,
const ParallelParkingParameters & parallel_parking_parameters);

PlannerType getPlannerType() override { return PlannerType::GEOMETRIC; };
boost::optional<PullOutPath> plan(Pose start_pose, Pose goal_pose) override;

GeometricParallelParking planner_;
ParallelParkingParameters parallel_parking_parameters_;
};
} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__GEOMETRIC_PULL_OUT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,63 +15,48 @@
#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_MODULE_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_MODULE_HPP_

#include "behavior_path_planner/scene_module/pull_out/geometric_pull_out.hpp"
#include "behavior_path_planner/scene_module/pull_out/pull_out_parameters.hpp"
#include "behavior_path_planner/scene_module/pull_out/pull_out_path.hpp"
#include "behavior_path_planner/scene_module/pull_out/shift_pull_out.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <vehicle_info_util/vehicle_info.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

#include <tf2/utils.h>

#include <deque>
#include <memory>
#include <string>
#include <utility>
#include <vector>

namespace behavior_path_planner
{
struct PullOutParameters
{
double min_stop_distance;
double stop_time;
double hysteresis_buffer_distance;
double pull_out_prepare_duration;
double pull_out_duration;
double pull_out_finish_judge_buffer;
double minimum_pull_out_velocity;
double prediction_duration;
double prediction_time_resolution;
double static_obstacle_velocity_thresh;
double maximum_deceleration;
int pull_out_sampling_num;
bool enable_collision_check_at_prepare_phase;
bool use_predicted_path_outside_lanelet;
bool use_all_predicted_path;
bool use_dynamic_object;
bool enable_blocked_by_obstacle;
double pull_out_search_distance;
double before_pull_out_straight_distance;
double after_pull_out_straight_distance;
double maximum_lateral_jerk;
double minimum_lateral_jerk;
double deceleration_interval;
};
using geometry_msgs::msg::PoseArray;
using lane_departure_checker::LaneDepartureChecker;

struct PullOutStatus
{
PathWithLaneId lane_follow_path;
PullOutPath pull_out_path;
PullOutPath retreat_path;
PullOutPath straight_back_path;
size_t current_path_idx = 0;
PlannerType planner_type = PlannerType::NONE;
PathWithLaneId backward_path;
lanelet::ConstLanelets current_lanes;
lanelet::ConstLanelets pull_out_lanes;
std::vector<uint64_t> lane_follow_lane_ids;
std::vector<uint64_t> pull_out_lane_ids;
bool is_safe;
double start_distance;
bool back_finished;
bool is_retreat_path_valid;
Pose backed_pose;
bool is_safe = false;
bool back_finished = false;
Pose pull_out_start_pose;
};

class PullOutModule : public SceneModuleInterface
Expand All @@ -91,44 +76,50 @@ class PullOutModule : public SceneModuleInterface
void onEntry() override;
void onExit() override;

void setParameters(const PullOutParameters & parameters);
void setParameters(const PullOutParameters & parameters) { parameters_ = parameters; }
void resetStatus();

private:
PullOutParameters parameters_;
vehicle_info_util::VehicleInfo vehicle_info_;

std::vector<std::shared_ptr<PullOutPlannerBase>> pull_out_planners_;
PullOutStatus status_;

double pull_out_lane_length_ = 200.0;
double check_distance_ = 100.0;
std::vector<Pose> backed_pose_candidates_;
PoseStamped backed_pose_;
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> odometry_buffer_;

PathWithLaneId getReferencePath() const;
std::unique_ptr<rclcpp::Time> last_route_received_time_;
std::unique_ptr<rclcpp::Time> last_pull_out_start_update_time_;

std::shared_ptr<PullOutPlannerBase> getCurrentPlanner() const;
lanelet::ConstLanelets getCurrentLanes() const;
lanelet::ConstLanelets getPullOutLanes(const lanelet::ConstLanelets & current_lanes) const;
std::pair<bool, bool> getSafePath(
const lanelet::ConstLanelets & pull_out_lanes, const double check_distance,
PullOutPath & safe_path) const;
std::pair<bool, bool> getSafeRetreatPath(
const lanelet::ConstLanelets & pull_out_lanes, const double check_distance,
RetreatPath & safe_backed_path, double & back_distance) const;

bool getBackDistance(
const lanelet::ConstLanelets & pullover_lanes, const double check_distance,
PullOutPath & safe_path, double & back_distance) const;
PathWithLaneId getFullPath() const;
ParallelParkingParameters getGeometricPullOutParameters() const;
std::vector<Pose> searchBackedPoses();

// turn signal
TurnSignalInfo calcTurnSignalInfo(const ShiftPoint & shift_point) const;
std::shared_ptr<LaneDepartureChecker> lane_departure_checker_;

// turn signal
TurnSignalInfo calcTurnSignalInfo(const Pose start_pose, const Pose end_pose) const;

void incrementPathIndex();
PathWithLaneId getCurrentPath() const;
void planWithPriorityOnEfficientPath(
const std::vector<Pose> & start_pose_candidates, const Pose & goal_pose);
void planWithPriorityOnShortBackDistance(
const std::vector<Pose> & start_pose_candidates, const Pose & goal_pose);
void updatePullOutStatus();
bool isInLane(
static bool isInLane(
const lanelet::ConstLanelet & candidate_lanelet,
const tier4_autoware_utils::LinearRing2d & vehicle_footprint) const;
bool isLongEnough(const lanelet::ConstLanelets & lanelets) const;
bool isSafe() const;
bool isNearEndOfLane() const;
bool isCurrentSpeedLow() const;
const tier4_autoware_utils::LinearRing2d & vehicle_footprint);
bool hasFinishedPullOut() const;
bool hasFinishedBack() const;
vehicle_info_util::VehicleInfo getVehicleInfo(
const BehaviorPathPlannerParameters & parameters) const;
void checkBackFinished();
bool isStopped();
bool hasFinishedCurrentPath();

void setDebugData() const;
};
} // namespace behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@

// Copyright 2022 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__SCENE_MODULE__PULL_OUT__PULL_OUT_PARAMETERS_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_PARAMETERS_HPP_

#include <string>

namespace behavior_path_planner
{
struct PullOutParameters
{
double th_arrived_distance;
double th_stopped_velocity;
double th_stopped_time;
double collision_check_margin;
double pull_out_finish_judge_buffer;
// shift pull out
bool enable_shift_pull_out;
double shift_pull_out_velocity;
int pull_out_sampling_num;
double before_pull_out_straight_distance;
double minimum_shift_pull_out_distance;
double maximum_lateral_jerk;
double minimum_lateral_jerk;
double deceleration_interval;
// geometric pull out
bool enable_geometric_pull_out;
double geometric_pull_out_velocity;
double arc_path_interval;
double lane_departure_margin;
double backward_velocity;
double pull_out_max_steer_angle;
// search start pose backward
std::string search_priority; // "efficient_path" or "short_back_distance"
bool enable_back;
double max_back_distance;
double backward_search_resolution;
double backward_path_update_duration;
};

} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_PARAMETERS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,23 +19,16 @@

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

#include <vector>

namespace behavior_path_planner
{
using autoware_auto_planning_msgs::msg::PathWithLaneId;
struct PullOutPath
{
PathWithLaneId path;
ShiftedPath shifted_path;
ShiftPoint shift_point;
double acceleration = 0.0;
double preparation_length = 0.0;
double pull_out_length = 0.0;
};

struct RetreatPath
{
behavior_path_planner::PullOutPath pull_out_path;
Pose backed_pose;
std::vector<PathWithLaneId> partial_paths;
Pose start_pose;
Pose end_pose;
};
} // namespace behavior_path_planner
#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_PATH_HPP_
Loading

0 comments on commit 1235738

Please sign in to comment.