-
Notifications
You must be signed in to change notification settings - Fork 20
/
behavior_path_planner_tree.xml
94 lines (94 loc) · 4.07 KB
/
behavior_path_planner_tree.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
<?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="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>
<!-- ////////// -->
<BehaviorTree ID="a">
<ReactiveFallback>
<Condition ID="LaneChange_CheckApproval"/>
<KeepRunningUntilFailure>
<Action ID="LaneChange_PlanCandidate" output="{output}"/>
</KeepRunningUntilFailure>
</ReactiveFallback>
</BehaviorTree>
<!-- ////////// -->
<BehaviorTree ID="b">
<ReactiveFallback>
<Condition ID="Avoidance_CheckApproval"/>
<KeepRunningUntilFailure>
<Action ID="Avoidance_PlanCandidate" output="{output}"/>
</KeepRunningUntilFailure>
</ReactiveFallback>
</BehaviorTree>
<!-- ////////// -->
<TreeNodesModel>
<Condition ID="Avoidance_CheckApproval"/>
<Action ID="Avoidance_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Action ID="Avoidance_PlanCandidate">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="Avoidance_Request"/>
<Condition ID="ExternalApproval"/>
<Condition ID="LaneChange_CheckApproval"/>
<Action ID="LaneChange_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Action ID="LaneChange_PlanCandidate">
<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<tier4_planning_msgs::PathWithLaneId_<std::allocator<void> > >">desc</output_port>
</Action>
<Action ID="LaneFollowing_PlanCandidate">
<output_port name="output_candidate" type="boost::optional<tier4_planning_msgs::PathWithLaneId_<std::allocator<void> > >">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"/>
<Condition ID="SideShift_CheckApproval"/>
<Action ID="SideShift_Plan">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Action ID="SideShift_PlanCandidate">
<output_port name="output" type="behavior_path_planner::BehaviorModuleOutput">desc</output_port>
</Action>
<Condition ID="SideShift_Request"/>
<SubTree ID="SubTree"/>
<SubTree ID="a"/>
<SubTree ID="b"/>
</TreeNodesModel>
<!-- ////////// -->
</root>