/
request_teleoperation.xml
53 lines (53 loc) · 3.02 KB
/
request_teleoperation.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
<?xml version='1.0' encoding='UTF-8'?>
<root BTCPP_format="4" main_tree_to_execute="Request Teleoperation">
<!-- The integer value used here for teleoperation mode comes from the moveit_studio_sdk_msgs/TeleoperationMode ROS message. -->
<BehaviorTree ID="Request Teleoperation" _description="Handles the different variations of teleoperation from the web UI, with the option of interactive user prompts and choosing the initial mode. Should be used as a subtree with port remapping as part of an another Objective." _favorite="false" _hardcoded="false">
<Control ID="Sequence">
<Action ID="Script" code="teleop_mode := 0"/>
<Control ID="Parallel" success_count="1" failure_count="1">
<Action ID="DoTeleoperateAction" enable_user_interaction="{enable_user_interaction}" user_interaction_prompt="{user_interaction_prompt}" initial_teleop_mode="{initial_teleop_mode}" current_teleop_mode="{teleop_mode}"/>
<Decorator ID="KeepRunningUntilFailure">
<Control ID="Sequence">
<!-- Closing and opening the gripper -->
<Decorator ID="ForceSuccess" _skipIf="teleop_mode != 7">
<SubTree ID="Close Gripper"/>
</Decorator>
<Decorator ID="ForceSuccess" _skipIf="teleop_mode != 6">
<SubTree ID="Open Gripper"/>
</Decorator>
<!-- Joint sliders interpolate to joint state -->
<Decorator ID="ForceSuccess" _while="teleop_mode == 5">
<Control ID="Sequence">
<Action ID="SwitchUIPrimaryView" primary_view_name="Visualization"/>
<SubTree ID="Interpolate to Joint State"/>
</Control>
</Decorator>
<!-- Interactive markers move to pose -->
<Decorator ID="ForceSuccess" _while="teleop_mode == 4">
<Control ID="Sequence">
<Action ID="SwitchUIPrimaryView" primary_view_name="Visualization"/>
<SubTree ID="Move to Pose" controller_names="/joint_trajectory_controller"/>
</Control>
</Decorator>
<!-- Waypoint buttons move to joint state -->
<Decorator ID="ForceSuccess" _while="teleop_mode == 3">
<Control ID="Sequence">
<Action ID="SwitchUIPrimaryView" primary_view_name="Visualization"/>
<SubTree ID="Move to Joint State"/>
</Control>
</Decorator>
<!-- Cartesian and joint jogging -->
<Control ID="Sequence" _while="teleop_mode == 2">
<Action ID="SwitchUIPrimaryView" primary_view_name="Visualization"/>
<Action ID="TeleoperateTwist" controller_name="servo_controller"/>
</Control>
<Control ID="Sequence" _while="teleop_mode == 1">
<Action ID="SwitchUIPrimaryView" primary_view_name="Visualization"/>
<Action ID="TeleoperateJointJog" controller_name="servo_controller"/>
</Control>
</Control>
</Decorator>
</Control>
</Control>
</BehaviorTree>
</root>