openarm_ros2/openarm_bimanual_moveit_config/config/openarm_bimanual.srdf
thomason 1a1084c627
Add moveit2 package with dual arm/gripper (#5)
* Create mujoco_ros2_control package

* Enable Mujoco hardware interface for OpenArm

* Verify connection with ros2_control

* Update actuators to pos/vel

* Add motor after creation

* Tune KD for smoother motion

* Restore realsense camera

* Change camera to be 10 tilt from vertical to match physical model

* Repair urdf to match physical robot

* Checkpoint moveit2_configuration

* Remove collision between camera and pedestal and remove additional ros2_control interfaces for mock

* Enable octomap perception

* Fix base_link to world transform

* Update openarm to support moveit2 bimanual planning with end effectors

* Improve safety of openarm_hardware zero position autocalibration

* Remove openarm_mujoco_ros2_control from moveit2 branch

* Restore sensor functionality
2025-04-22 18:46:27 +09:00

316 lines
21 KiB
XML

<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="openarm_bimanual">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="left_arm">
<link name="left_link1"/>
<link name="left_link2"/>
<link name="left_link3"/>
<link name="left_link4"/>
<link name="left_link5"/>
<link name="left_link6"/>
<link name="left_link7"/>
<link name="left_link8"/>
<link name="left_gripper_center"/>
<joint name="left_rev1"/>
<joint name="left_rev2"/>
<joint name="left_rev3"/>
<joint name="left_rev4"/>
<joint name="left_rev5"/>
<joint name="left_rev6"/>
<joint name="left_rev7"/>
<joint name="left_virtual_gripper_center"/>
<chain base_link="left_link1" tip_link="left_link8"/>
</group>
<group name="right_arm">
<link name="right_link1"/>
<link name="right_link2"/>
<link name="right_link3"/>
<link name="right_link4"/>
<link name="right_link5"/>
<link name="right_link6"/>
<link name="right_link7"/>
<link name="right_link8"/>
<link name="right_gripper_center"/>
<joint name="right_rev1"/>
<joint name="right_rev2"/>
<joint name="right_rev3"/>
<joint name="right_rev4"/>
<joint name="right_rev5"/>
<joint name="right_rev6"/>
<joint name="right_rev7"/>
<joint name="right_virtual_gripper_center"/>
<chain base_link="right_link1" tip_link="right_link8"/>
</group>
<group name="left_gripper">
<link name="left_link_left_jaw"/>
<joint name="left_left_pris1"/>
</group>
<group name="right_gripper">
<link name="right_link_left_jaw"/>
<joint name="right_left_pris1"/>
</group>
<group name="left_side">
<group name="left_arm"/>
<group name="left_gripper"/>
</group>
<group name="right_side">
<group name="right_gripper"/>
<group name="right_arm"/>
</group>
<group name="upper_body">
<group name="left_side"/>
<group name="right_side"/>
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="upper_body">
<joint name="left_left_pris1" value="0"/>
<joint name="left_rev1" value="0"/>
<joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0"/>
<joint name="left_rev4" value="0"/>
<joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/>
<joint name="right_rev1" value="0"/>
<joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/>
<joint name="right_rev4" value="0"/>
<joint name="right_rev5" value="0"/>
<joint name="right_rev6" value="0"/>
<joint name="right_rev7" value="0"/>
</group_state>
<group_state name="ready" group="upper_body">
<joint name="left_left_pris1" value="0"/>
<joint name="left_rev1" value="0.2"/>
<joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0"/>
<joint name="left_rev4" value="1"/>
<joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/>
<joint name="right_rev1" value="-0.2"/>
<joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/>
<joint name="right_rev4" value="1"/>
<joint name="right_rev5" value="0"/>
<joint name="right_rev6" value="0"/>
<joint name="right_rev7" value="0"/>
</group_state>
<group_state name="open" group="left_gripper">
<joint name="left_left_pris1" value="0"/>
</group_state>
<group_state name="half_closed" group="left_gripper">
<joint name="left_left_pris1" value="-0.0225"/>
</group_state>
<group_state name="closed" group="left_gripper">
<joint name="left_left_pris1" value="-0.0451"/>
</group_state>
<group_state name="open" group="right_gripper">
<joint name="right_left_pris1" value="0"/>
</group_state>
<group_state name="half_closed" group="right_gripper">
<joint name="right_left_pris1" value="-0.0225"/>
</group_state>
<group_state name="center grip" group="upper_body">
<joint name="left_left_pris1" value="0"/>
<joint name="left_rev1" value="0.2"/>
<joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0.5"/>
<joint name="left_rev4" value="1.6"/>
<joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/>
<joint name="right_rev1" value="-0.2"/>
<joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="-0.5"/>
<joint name="right_rev4" value="1.8379"/>
<joint name="right_rev5" value="0.0116"/>
<joint name="right_rev6" value="-0.2517"/>
<joint name="right_rev7" value="0.0053"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="left_gripper" parent_link="left_link8" group="left_gripper" parent_group="left_side"/>
<end_effector name="right_gripper" parent_link="right_link8" group="right_gripper" parent_group="right_side"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="base_link" child_link="pedestal_link"/>
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="left_right_pris2"/>
<passive_joint name="right_right_pris2"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="camera_link" link2="pedestal_link" reason="Adjacent"/>
<disable_collisions link1="left_link1" link2="left_link2" reason="Adjacent"/>
<disable_collisions link1="left_link1" link2="left_link3" reason="User"/>
<disable_collisions link1="left_link1" link2="left_link4" reason="User"/>
<disable_collisions link1="left_link1" link2="left_link5" reason="Never"/>
<disable_collisions link1="left_link1" link2="pedestal_link" reason="Adjacent"/>
<disable_collisions link1="left_link1" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link1" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link3" reason="Adjacent"/>
<disable_collisions link1="left_link2" link2="left_link4" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link5" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link6" reason="Never"/>
<disable_collisions link1="left_link2" link2="left_link7" reason="Never"/>
<disable_collisions link1="left_link2" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link2" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link3" link2="left_link4" reason="Adjacent"/>
<disable_collisions link1="left_link3" link2="left_link5" reason="Never"/>
<disable_collisions link1="left_link3" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link3" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="left_link5" reason="Adjacent"/>
<disable_collisions link1="left_link4" link2="left_link7" reason="Never"/>
<disable_collisions link1="left_link4" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link4" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link6" reason="Adjacent"/>
<disable_collisions link1="left_link5" link2="left_link7" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link8" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="pedestal_link" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link5" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="left_link7" reason="Adjacent"/>
<disable_collisions link1="left_link6" link2="left_link8" reason="Default"/>
<disable_collisions link1="left_link6" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link6" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="left_link8" reason="Adjacent"/>
<disable_collisions link1="left_link7" link2="left_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link7" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link8" link2="left_link_left_jaw" reason="Adjacent"/>
<disable_collisions link1="left_link8" link2="left_link_right_jaw" reason="Adjacent"/>
<disable_collisions link1="left_link8" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link8" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="left_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link8" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link_left_jaw" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link1" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link2" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link3" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link4" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link5" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link6" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link7" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="left_link_right_jaw" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link1" reason="Adjacent"/>
<disable_collisions link1="pedestal_link" link2="right_link2" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link3" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link4" reason="Never"/>
<disable_collisions link1="pedestal_link" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link1" link2="right_link2" reason="Adjacent"/>
<disable_collisions link1="right_link1" link2="right_link3" reason="User"/>
<disable_collisions link1="right_link1" link2="right_link4" reason="User"/>
<disable_collisions link1="right_link1" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link3" reason="Adjacent"/>
<disable_collisions link1="right_link2" link2="right_link4" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link6" reason="Never"/>
<disable_collisions link1="right_link2" link2="right_link7" reason="Never"/>
<disable_collisions link1="right_link3" link2="right_link4" reason="Adjacent"/>
<disable_collisions link1="right_link3" link2="right_link5" reason="Never"/>
<disable_collisions link1="right_link4" link2="right_link5" reason="Adjacent"/>
<disable_collisions link1="right_link4" link2="right_link7" reason="Never"/>
<disable_collisions link1="right_link4" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link4" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link6" reason="Adjacent"/>
<disable_collisions link1="right_link5" link2="right_link7" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link8" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link5" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link6" link2="right_link7" reason="Adjacent"/>
<disable_collisions link1="right_link6" link2="right_link8" reason="Default"/>
<disable_collisions link1="right_link6" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link6" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link7" link2="right_link8" reason="Adjacent"/>
<disable_collisions link1="right_link7" link2="right_link_left_jaw" reason="Never"/>
<disable_collisions link1="right_link7" link2="right_link_right_jaw" reason="Never"/>
<disable_collisions link1="right_link8" link2="right_link_left_jaw" reason="Adjacent"/>
<disable_collisions link1="right_link8" link2="right_link_right_jaw" reason="Adjacent"/>
<disable_collisions link1="right_link_left_jaw" link2="right_link_right_jaw" reason="Never"/>
</robot>