Skip to content

Commit

Permalink
feat(behavior_path_planner): disable external request lane change in …
Browse files Browse the repository at this point in the history
…default tree

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
rej55 committed Jan 18, 2023
1 parent 0863e69 commit 81cf203
Show file tree
Hide file tree
Showing 2 changed files with 76 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
<Condition ID="SideShift_Request"/>
<Action ID="SideShift_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<!-- <ReactiveSequence>
<Condition ID="ExternalRequestLaneChangeRight_Request"/>
<Action ID="ExternalRequestLaneChangeRight_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="ExternalRequestLaneChangeLeft_Request"/>
<Action ID="ExternalRequestLaneChangeLeft_Plan" output="{output}"/>
</ReactiveSequence>
</ReactiveSequence> -->
<ReactiveSequence>
<Condition ID="LaneChange_Request"/>
<Action ID="LaneChange_Plan" output="{output}"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<?xml version="1.0"?>
<root main_tree_to_execute="BehaviorTree">
<!-- ////////// -->
<BehaviorTree ID="BehaviorTree">
<Fallback>
<ReactiveSequence>
<Condition ID="PullOver_Request"/>
<Action ID="PullOver_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="PullOut_Request"/>
<Action ID="PullOut_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="SideShift_Request"/>
<Action ID="SideShift_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="ExternalRequestLaneChangeRight_Request"/>
<Action ID="ExternalRequestLaneChangeRight_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="ExternalRequestLaneChangeLeft_Request"/>
<Action ID="ExternalRequestLaneChangeLeft_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="LaneChange_Request"/>
<Action ID="LaneChange_Plan" output="{output}"/>
</ReactiveSequence>
<ReactiveSequence>
<Condition ID="Avoidance_Request"/>
<Action ID="Avoidance_Plan" output="{output}"/>
</ReactiveSequence>
<Action ID="LaneFollowing_Plan" output="{output}"/>
</Fallback>
</BehaviorTree>
<!-- ////////// -->
<TreeNodesModel>
<Action ID="Avoidance_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="Avoidance_Request"/>
<Condition ID="ExternalApproval"/>
<Action ID="ExternalRequestLaneChangeRight_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="ExternalRequestLaneChangeRight_Request"/>
<Action ID="ExternalRequestLaneChangeLeft_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="ExternalRequestLaneChangeLeft_Request"/>
<Action ID="LaneChange_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="LaneChange_Request"/>
<Action ID="LaneFollowing_Plan">
<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">
<output_port name="output"/>
</Action>
<Condition ID="PullOut_Request"/>
<Action ID="PullOver_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="PullOver_Request"/>
<Action ID="SideShift_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="SideShift_Request"/>
</TreeNodesModel>
<!-- ////////// -->
</root>

0 comments on commit 81cf203

Please sign in to comment.