Skip to content

Commit

Permalink
refactor(start_planner): rename pull out to start planner (autowarefo…
Browse files Browse the repository at this point in the history
…undation#565)

* refactor(pull_out): consolidate similar function (autowarefoundation#3803)

* consolidate planWithPriority function

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* add comments

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* fix

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* refactoring

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* refactoring

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* change arg type

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>

* Update planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp

* Update planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp

---------

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
Co-authored-by: Kosuke Takeuchi <kosuke.tnp@gmail.com>

* refactor(start_planner): rename pull out to start planner (autowarefoundation#3908)

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

---------

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
Co-authored-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
  • Loading branch information
kosuke55 and kyoichi-sugahara authored Jun 8, 2023
1 parent 5576724 commit d1a1fde
Show file tree
Hide file tree
Showing 45 changed files with 299 additions and 321 deletions.
6 changes: 3 additions & 3 deletions common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ std::string getModuleName(const uint8_t module_type)
case Module::GOAL_PLANNER: {
return "goal_planner";
}
case Module::PULL_OUT: {
return "pull_out";
case Module::START_PLANNER: {
return "start_planner";
}
case Module::TRAFFIC_LIGHT: {
return "traffic_light";
Expand Down Expand Up @@ -105,7 +105,7 @@ bool isPathChangeModule(const uint8_t module_type)
module_type == Module::EXT_REQUEST_LANE_CHANGE_RIGHT ||
module_type == Module::AVOIDANCE_BY_LC_LEFT || module_type == Module::AVOIDANCE_BY_LC_RIGHT ||
module_type == Module::AVOIDANCE_LEFT || module_type == Module::AVOIDANCE_RIGHT ||
module_type == Module::GOAL_PLANNER || module_type == Module::PULL_OUT) {
module_type == Module::GOAL_PLANNER || module_type == Module::START_PLANNER) {
return true;
}
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -232,8 +232,8 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray::
case SteeringFactor::STATION:
label->setText("STATION");
break;
case SteeringFactor::PULL_OUT:
label->setText("PULL_OUT");
case SteeringFactor::START_PLANNER:
label->setText("START_PLANNER");
break;
case SteeringFactor::GOAL_PLANNER:
label->setText("GOAL_PLANNER");
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/launch/planning.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<arg name="dynamic_avoidance_param_path"/>
<arg name="lane_change_param_path"/>
<arg name="goal_planner_param_path"/>
<arg name="pull_out_param_path"/>
<arg name="start_planner_param_path"/>
<arg name="drivable_area_expansion_param_path"/>
<arg name="behavior_path_planner_param_path"/>
<!-- behavior velocity planner -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ def launch_setup(context, *args, **kwargs):
lane_change_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("goal_planner_param_path").perform(context), "r") as f:
goal_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("pull_out_param_path").perform(context), "r") as f:
pull_out_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("start_planner_param_path").perform(context), "r") as f:
start_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("drivable_area_expansion_param_path").perform(context), "r") as f:
drivable_area_expansion_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("scene_module_manager_param_path").perform(context), "r") as f:
Expand Down Expand Up @@ -96,7 +96,7 @@ def launch_setup(context, *args, **kwargs):
dynamic_avoidance_param,
lane_change_param,
goal_planner_param,
pull_out_param,
start_planner_param,
drivable_area_expansion_param,
scene_module_manager_param,
behavior_path_planner_param,
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<maintainer email="zulfaqar.azmi@tier4.jp">Zulfaqar Azmi</maintainer>
<!-- goal planner module -->
<maintainer email="kosuke.takeuchi@tier4.jp">Kosuke Takeuchi</maintainer>
<!-- pull out module -->
<!-- start planner module -->
<maintainer email="kosuke.takeuchi@tier4.jp">Kosuke Takeuchi</maintainer>
<!-- side shift module -->
<maintainer email="fumiya.watanabe@tier4.jp">Fumiya Watanabe</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1225,15 +1225,15 @@ Visualization Manager:
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
Name: PullOut
Name: StartPlanner
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/pullout
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/startplanner
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1226,15 +1226,15 @@ Visualization Manager:
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
Name: PullOut
Name: StartPlanner
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/pullout
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/startplanner
Value: false
- Class: rviz_default_plugins/MarkerArray
Enabled: false
Expand Down
10 changes: 5 additions & 5 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ set(common_src
src/scene_module/scene_module_visitor.cpp
src/scene_module/avoidance/avoidance_module.cpp
src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp
src/scene_module/pull_out/pull_out_module.cpp
src/scene_module/start_planner/start_planner_module.cpp
src/scene_module/goal_planner/goal_planner_module.cpp
src/scene_module/side_shift/side_shift_module.cpp
src/scene_module/lane_change/interface.cpp
Expand All @@ -35,9 +35,9 @@ set(common_src
src/utils/goal_planner/freespace_pull_over.cpp
src/utils/goal_planner/goal_searcher.cpp
src/utils/goal_planner/default_fixed_goal_planner.cpp
src/utils/pull_out/util.cpp
src/utils/pull_out/shift_pull_out.cpp
src/utils/pull_out/geometric_pull_out.cpp
src/utils/start_planner/util.cpp
src/utils/start_planner/shift_pull_out.cpp
src/utils/start_planner/geometric_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 Expand Up @@ -67,7 +67,7 @@ else()
src/planner_manager.cpp
src/scene_module/avoidance/manager.cpp
src/scene_module/dynamic_avoidance/manager.cpp
src/scene_module/pull_out/manager.cpp
src/scene_module/start_planner/manager.cpp
src/scene_module/goal_planner/manager.cpp
src/scene_module/side_shift/manager.cpp
src/scene_module/lane_change/manager.cpp
Expand Down
20 changes: 10 additions & 10 deletions planning/behavior_path_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,16 @@ The `behavior_path_planner` module is responsible to generate

Behavior path planner has following scene modules.

| Name | Description | Details |
| :------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------- |
| Lane Following | this module generates reference path from lanelet centerline. | LINK |
| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_design.md) |
| Avoidance By LC | this module generates lane change path when there is objects that should be avoid. | LINK |
| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](./docs/behavior_path_planner_lane_change_design.md) |
| External Lane Change | WIP | LINK |
| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](./docs/behavior_path_planner_goal_planner_design.md) |
| Pull Out | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](./docs/behavior_path_planner_pull_out_design.md) |
| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](./docs/behavior_path_planner_side_shift_design.md) |
| Name | Description | Details |
| :------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :----------------------------------------------------------- |
| Lane Following | this module generates reference path from lanelet centerline. | LINK |
| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_design.md) |
| Avoidance By LC | this module generates lane change path when there is objects that should be avoid. | LINK |
| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](./docs/behavior_path_planner_lane_change_design.md) |
| External Lane Change | WIP | LINK |
| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](./docs/behavior_path_planner_goal_planner_design.md) |
| Pull Out | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](./docs/behavior_path_planner_start_planner_design.md) |
| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](./docs/behavior_path_planner_side_shift_design.md) |

![behavior_modules](./image/behavior_modules.png)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
<Action ID="GoalPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Action ID="PullOut_Plan" output="{output}"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="StartPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="SideShift_Request"/>
Expand Down Expand Up @@ -57,10 +57,10 @@
<output_port name="output" type="boost::optional&lt;tier4_planning_msgs::PathWithLaneId_&lt;std::allocator&lt;void&gt; &gt; &gt;">desc</output_port>
</Action>
<Condition ID="LaneFollowing_Request"/>
<Action ID="PullOut_Plan">
<Action ID="StartPlanner_Plan">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Request"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="GoalPlanner_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
<Action ID="GoalPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Action ID="PullOut_Plan" output="{output}"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="StartPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="LaneChange_Request"/>
Expand Down Expand Up @@ -62,10 +62,10 @@
<output_port name="output_candidate" type="boost::optional&lt;tier4_planning_msgs::PathWithLaneId_&lt;std::allocator&lt;void&gt; &gt; &gt;">desc</output_port>
</Action>
<Condition ID="LaneFollowing_Request"/>
<Action ID="PullOut_Plan">
<Action ID="StartPlanner_Plan">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Request"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="GoalPlanner_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@
<Action ID="GoalPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Condition ID="PullOut_Ready"/>
<Action ID="PullOut_Plan" output="{output}"/>
<Condition ID="StartPlanner_Request"/>
<Condition ID="StartPlanner_Ready"/>
<Action ID="StartPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="LaneChange_Request"/>
Expand Down Expand Up @@ -73,11 +73,11 @@
</Action>
<Condition ID="LaneFollowing_Ready"/>
<Condition ID="LaneFollowing_Request"/>
<Action ID="PullOut_Plan">
<Action ID="StartPlanner_Plan">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Ready"/>
<Condition ID="PullOut_Request"/>
<Condition ID="StartPlanner_Ready"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="GoalPlanner_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@
<Action ID="GoalPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Condition ID="PullOut_Ready"/>
<Action ID="PullOut_Plan" output="{output}"/>
<Condition ID="StartPlanner_Request"/>
<Condition ID="StartPlanner_Ready"/>
<Action ID="StartPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="SideShift_Request"/>
Expand Down Expand Up @@ -83,11 +83,11 @@
</Action>
<Condition ID="LaneFollowing_Ready"/>
<Condition ID="LaneFollowing_Request"/>
<Action ID="PullOut_Plan">
<Action ID="StartPlanner_Plan">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Ready"/>
<Condition ID="PullOut_Request"/>
<Condition ID="StartPlanner_Ready"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="GoalPlanner_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@
<Action ID="GoalPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Condition ID="PullOut_Ready"/>
<Action ID="PullOut_Plan" output="{output}"/>
<Condition ID="StartPlanner_Request"/>
<Condition ID="StartPlanner_Ready"/>
<Action ID="StartPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="LaneChange_Request"/>
Expand Down Expand Up @@ -73,11 +73,11 @@
</Action>
<Condition ID="LaneFollowing_Ready"/>
<Condition ID="LaneFollowing_Request"/>
<Action ID="PullOut_Plan">
<Action ID="StartPlanner_Plan">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Ready"/>
<Condition ID="PullOut_Request"/>
<Condition ID="StartPlanner_Ready"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="GoalPlanner_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
<Action ID="GoalPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Action ID="PullOut_Plan" output="{output}"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="StartPlanner_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="SideShift_Request"/>
Expand Down Expand Up @@ -57,10 +57,10 @@
<output_port name="output" type="boost::optional&lt;tier4_planning_msgs::PathWithLaneId_&lt;std::allocator&lt;void&gt; &gt; &gt;">desc</output_port>
</Action>
<Condition ID="LaneFollowing_Request"/>
<Action ID="PullOut_Plan">
<Action ID="StartPlanner_Plan">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Request"/>
<Condition ID="StartPlanner_Request"/>
<Action ID="GoalPlanner_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
priority: 5
max_module_size: 1

pull_out:
start_planner:
enable_module: true
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**:
ros__parameters:
pull_out:
start_planner:
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
Expand Down
Loading

0 comments on commit d1a1fde

Please sign in to comment.