diff --git a/src/fanuc_sim/config/config.yaml b/src/fanuc_sim/config/config.yaml
index a65f9e0f..408a64c6 100644
--- a/src/fanuc_sim/config/config.yaml
+++ b/src/fanuc_sim/config/config.yaml
@@ -43,6 +43,7 @@ hardware:
urdf_params:
# Use "mock", "mujoco", or "real"
- hardware_interface: "mujoco"
+ - mujoco_viewer: "false"
# Sets ROS global params for launch.
# [Optional]
@@ -112,6 +113,8 @@ ros2_control:
- "joint_trajectory_controller"
- "servo_controller"
- "joint_state_broadcaster"
+ - "tool_attach_controller"
+ - "suction_cup_controller"
# - "servo_controller"
# Load but do not start these controllers so they can be activated later if needed.
# [Optional, default=[]]
diff --git a/src/fanuc_sim/config/control/picknik_fanuc.ros2_control.yaml b/src/fanuc_sim/config/control/picknik_fanuc.ros2_control.yaml
index 68aedf87..c8111bdd 100644
--- a/src/fanuc_sim/config/control/picknik_fanuc.ros2_control.yaml
+++ b/src/fanuc_sim/config/control/picknik_fanuc.ros2_control.yaml
@@ -7,6 +7,29 @@ controller_manager:
type: joint_trajectory_controller/JointTrajectoryController
servo_controller:
type: joint_trajectory_controller/JointTrajectoryController
+ # A controller to enable/disable the tool attachment interface at the robot flange.
+ # In sim, this is modeled as a weld constraint in Mujoco.
+ # In a real robot, this controller would activate a mechanism to attach/detach the tool at the robot flange.
+ tool_attach_controller:
+ type: position_controllers/GripperActionController
+ # A controller to enable/disable the suction cup.
+ # In sim, this is modeled as a weld constraint in Mujoco.
+ # In a real robot, this controller would activate / deactivate a suction cup mechanism.
+ suction_cup_controller:
+ type: position_controllers/GripperActionController
+
+
+tool_attach_controller:
+ ros__parameters:
+ default: true
+ joint: suction_cup_tool_interface
+ allow_stalling: true
+
+suction_cup_controller:
+ ros__parameters:
+ default: true
+ joint: suction_cup_tool_tip
+ allow_stalling: true
joint_state_broadcaster:
ros__parameters:
diff --git a/src/fanuc_sim/config/moveit/picknik_fanuc.srdf b/src/fanuc_sim/config/moveit/picknik_fanuc.srdf
index 3fb19407..81eb1627 100644
--- a/src/fanuc_sim/config/moveit/picknik_fanuc.srdf
+++ b/src/fanuc_sim/config/moveit/picknik_fanuc.srdf
@@ -19,6 +19,7 @@
+
diff --git a/src/fanuc_sim/description/fanuc_lrmate200id.ros2_control.xacro b/src/fanuc_sim/description/fanuc_lrmate200id.ros2_control.xacro
index e926a49e..a0788da1 100644
--- a/src/fanuc_sim/description/fanuc_lrmate200id.ros2_control.xacro
+++ b/src/fanuc_sim/description/fanuc_lrmate200id.ros2_control.xacro
@@ -5,6 +5,7 @@
params="name initial_positions_file hardware_interface mujoco_model"
>
+
picknik_mujoco_ros/MujocoSystem
$(arg mujoco_model)
fanuc_sim
+ $(arg mujoco_viewer)
10
60
10
diff --git a/src/fanuc_sim/description/picknik_fanuc.xacro b/src/fanuc_sim/description/picknik_fanuc.xacro
index 885c3fe4..7e8a4162 100644
--- a/src/fanuc_sim/description/picknik_fanuc.xacro
+++ b/src/fanuc_sim/description/picknik_fanuc.xacro
@@ -13,12 +13,61 @@
filename="$(find fanuc_sim)/description/fanuc_lrmate200id.ros2_control.xacro"
/>
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
+
+
@@ -82,6 +83,7 @@
+
+
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/description/tool.urdf b/src/fanuc_sim/description/tool.urdf
new file mode 100644
index 00000000..055ee7aa
--- /dev/null
+++ b/src/fanuc_sim/description/tool.urdf
@@ -0,0 +1,42 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/description/tool.xml b/src/fanuc_sim/description/tool.xml
new file mode 100644
index 00000000..f00819a6
--- /dev/null
+++ b/src/fanuc_sim/description/tool.xml
@@ -0,0 +1,44 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/activate_vacuum.xml b/src/fanuc_sim/objectives/activate_vacuum.xml
new file mode 100644
index 00000000..3cd48867
--- /dev/null
+++ b/src/fanuc_sim/objectives/activate_vacuum.xml
@@ -0,0 +1,19 @@
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/close_gripper.xml b/src/fanuc_sim/objectives/close_gripper.xml
deleted file mode 100644
index ac4fe639..00000000
--- a/src/fanuc_sim/objectives/close_gripper.xml
+++ /dev/null
@@ -1,7 +0,0 @@
-
-
-
-
-
-
-
diff --git a/src/fanuc_sim/objectives/deactivate_vacuum.xml b/src/fanuc_sim/objectives/deactivate_vacuum.xml
new file mode 100644
index 00000000..36b49c3f
--- /dev/null
+++ b/src/fanuc_sim/objectives/deactivate_vacuum.xml
@@ -0,0 +1,20 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/open_gripper.xml b/src/fanuc_sim/objectives/open_gripper.xml
deleted file mode 100644
index 9b25c0c2..00000000
--- a/src/fanuc_sim/objectives/open_gripper.xml
+++ /dev/null
@@ -1,8 +0,0 @@
-
-
-
-
-
-
-
-
diff --git a/src/fanuc_sim/objectives/pick_up_block_with_tool.xml b/src/fanuc_sim/objectives/pick_up_block_with_tool.xml
new file mode 100644
index 00000000..1733a05d
--- /dev/null
+++ b/src/fanuc_sim/objectives/pick_up_block_with_tool.xml
@@ -0,0 +1,82 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/pick_up_tool.xml b/src/fanuc_sim/objectives/pick_up_tool.xml
new file mode 100644
index 00000000..18486e77
--- /dev/null
+++ b/src/fanuc_sim/objectives/pick_up_tool.xml
@@ -0,0 +1,95 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/place_tool_in_tool_holder.xml b/src/fanuc_sim/objectives/place_tool_in_tool_holder.xml
new file mode 100644
index 00000000..7d1c4c4c
--- /dev/null
+++ b/src/fanuc_sim/objectives/place_tool_in_tool_holder.xml
@@ -0,0 +1,83 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/request_teleoperation.xml b/src/fanuc_sim/objectives/request_teleoperation.xml
index e4c00eaa..6e76924b 100644
--- a/src/fanuc_sim/objectives/request_teleoperation.xml
+++ b/src/fanuc_sim/objectives/request_teleoperation.xml
@@ -21,10 +21,10 @@
-
+
-
+
diff --git a/src/fanuc_sim/objectives/retract.xml b/src/fanuc_sim/objectives/retract.xml
new file mode 100644
index 00000000..2974cfa1
--- /dev/null
+++ b/src/fanuc_sim/objectives/retract.xml
@@ -0,0 +1,50 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/setup_planning_scene.xml b/src/fanuc_sim/objectives/setup_planning_scene.xml
new file mode 100644
index 00000000..4751fbfb
--- /dev/null
+++ b/src/fanuc_sim/objectives/setup_planning_scene.xml
@@ -0,0 +1,27 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/fanuc_sim/objectives/tool_attachment_example.xml b/src/fanuc_sim/objectives/tool_attachment_example.xml
new file mode 100644
index 00000000..35769742
--- /dev/null
+++ b/src/fanuc_sim/objectives/tool_attachment_example.xml
@@ -0,0 +1,20 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/picknik_accessories b/src/picknik_accessories
index 69bfb7cc..45ccc593 160000
--- a/src/picknik_accessories
+++ b/src/picknik_accessories
@@ -1 +1 @@
-Subproject commit 69bfb7ccbfa7b9712cf1c2f13ee1280eac6f0430
+Subproject commit 45ccc593c7d3ef6179e0a2d7c87e503c67a28d39