Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 0 additions & 20 deletions src/fanuc_sim/objectives/request_teleoperation.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,6 @@
<!--Joint sliders interpolate to joint state-->
<Decorator ID="ForceSuccess" _while="teleop_mode == 5">
<Control ID="Sequence">
<Action
ID="SwitchUIPrimaryView"
primary_view_name="Visualization"
/>
<Control ID="Fallback" name="root">
<Control ID="Sequence">
<Action
Expand Down Expand Up @@ -67,10 +63,6 @@
<!--Interactive markers move to pose-->
<Decorator ID="ForceSuccess" _while="teleop_mode == 4">
<Control ID="Sequence">
<Action
ID="SwitchUIPrimaryView"
primary_view_name="Visualization"
/>
<Control ID="Fallback" name="root">
<Control ID="Sequence">
<Action
Expand Down Expand Up @@ -105,10 +97,6 @@
<!--Waypoint buttons move to joint state-->
<Decorator ID="ForceSuccess" _while="teleop_mode == 3">
<Control ID="Sequence">
<Action
ID="SwitchUIPrimaryView"
primary_view_name="Visualization"
/>
<Control ID="Fallback" name="root">
<Control ID="Sequence">
<Action
Expand Down Expand Up @@ -142,20 +130,12 @@
</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"
Expand Down
7 changes: 5 additions & 2 deletions src/lab_sim/objectives/add_waypoints_to_mtc_task.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
<?xml version="1.0" encoding="utf-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Add Waypoints to MTC Task">
<!--//////////-->
<BehaviorTree ID="Add Waypoints to MTC Task">
<BehaviorTree
ID="Add Waypoints to MTC Task"
_subtreeOnly="true"
_description=""
>
<Control ID="Sequence">
<Action
ID="RetrieveWaypoint"
Expand Down
7 changes: 6 additions & 1 deletion src/lab_sim/objectives/create_pose_vector.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
<root BTCPP_format="4" main_tree_to_execute="Create Pose Vector">
<!--//////////-->
<BehaviorTree ID="Create Pose Vector" _favorite="false">
<BehaviorTree
ID="Create Pose Vector"
_favorite="false"
_subtreeOnly="true"
_description=""
>
<Control ID="Sequence">
<Action
ID="CreateStampedPose"
Expand Down
6 changes: 5 additions & 1 deletion src/lab_sim/objectives/get_april_tag_pose_from_image.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
<root BTCPP_format="4" main_tree_to_execute="Get AprilTag Pose from Image">
<!-- ////////// -->
<BehaviorTree ID="Get AprilTag Pose from Image">
<BehaviorTree
ID="Get AprilTag Pose from Image"
_subtreeOnly="true"
_description=""
>
<Control ID="Sequence">
<!--Get tag pose estimate in world frame-->
<Action
Expand Down
Loading
Loading