forked from tier4/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
feat(behavior_path_planner): update pull out (tier4#1438)
* 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
Showing
24 changed files
with
1,172 additions
and
1,210 deletions.
There are no files selected for viewing
41 changes: 23 additions & 18 deletions
41
...lanning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
42 changes: 23 additions & 19 deletions
42
planning/behavior_path_planner/config/pull_out/pull_out.param.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
41 changes: 41 additions & 0 deletions
41
...r_path_planner/include/behavior_path_planner/scene_module/pull_out/geometric_pull_out.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
56 changes: 56 additions & 0 deletions
56
..._path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_parameters.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.