simple_gz_gripper/urdf/simple_gripper_macro.xacro
2025-06-03 15:39:15 +03:00

128 lines
3.8 KiB
XML

<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="gripper_scaled_up_macro">
<xacro:macro name="simple_parallel_gripper" params="prefix parent *origin">
<xacro:include filename="$(find simple_gz_gripper)/urdf/simple_gripper_macro.ros2_control.xacro" />
<!-- gripper base -->
<link name="${prefix}gripper_base">
<visual>
<geometry>
<box size="0.03334 0.06666 0.06666" />
</geometry>
<origin xyz="0 0 0.03334" />
<material name="violet">
<color rgba="0.4 0.18 0.57 1.0" />
</material>
</visual>
<collision>
<geometry>
<box size="0.03334 0.06666 0.06666" />
</geometry>
<origin xyz="0 0 0.03334" />
</collision>
<inertial>
<origin xyz="0 0 0.03334" />
<mass value="0.02" />
<inertia
ixx="1.679e-05" ixy="0.0" ixz="0.0"
iyy="7.437e-06" iyz="0.0"
izz="7.437e-06" />
</inertial>
</link>
<!-- finger right -->
<link name="${prefix}finger_right">
<visual>
<geometry>
<box size="0.02666 0.00666 0.06666" />
</geometry>
<origin xyz="0 -0.00334 0.03334" />
<material name="grey">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<geometry>
<box size="0.02666 0.00666 0.06666" />
</geometry>
<origin xyz="0 -0.00334 0.03334" />
<material name="grey">
<color rgba="0.2 0.2 0.2 1" />
</material>
</collision>
<inertial>
<origin xyz="0 0.00334 0.03334" />
<mass value="0.009876" />
<inertia
ixx="3.694e-06" ixy="0.0" ixz="0.0"
iyy="4.241e-06" iyz="0.0"
izz="6.213e-07" />
</inertial>
</link>
<!-- finger left -->
<link name="${prefix}finger_left">
<visual>
<geometry>
<box size="0.02666 0.00666 0.06666" />
</geometry>
<origin xyz="0 -0.00334 0.03334" />
<material name="grey">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<geometry>
<box size="0.02666 0.00666 0.06666" />
</geometry>
<origin xyz="0 -0.00334 0.03334" />
<material name="grey">
<color rgba="0.2 0.2 0.2 1" />
</material>
</collision>
<inertial>
<origin xyz="0 0.00334 0.03334" />
<mass value="0.009876" />
<inertia
ixx="3.694e-06" ixy="0.0" ixz="0.0"
iyy="4.241e-06" iyz="0.0"
izz="6.213e-07" />
</inertial>
</link>
<!-- joint from parent -->
<joint name="${prefix}base_fixed_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${prefix}gripper_base" />
</joint>
<!-- finger joints -->
<joint name="${prefix}right_finger_joint" type="prismatic">
<axis xyz="0 1 0" />
<origin xyz="0.0 0.0 0.06666" rpy="0.0 0.0 0.0" />
<parent link="${prefix}gripper_base" />
<child link="${prefix}finger_right" />
<limit effort="10.0" lower="0" upper="0.02534" velocity="1.0" />
<!-- <dynamics damping="2.0" friction="1.0"/> -->
</joint>
<joint name="${prefix}left_finger_joint" type="prismatic">
<mimic joint="${prefix}right_finger_joint"/>
<axis xyz="0 1 0" />
<origin xyz="0.0 0.0 0.06666" rpy="0.0 0.0 3.1415926535" />
<parent link="${prefix}gripper_base" />
<child link="${prefix}finger_left" />
<limit effort="10.0" lower="0" upper="0.02534" velocity="1.0" />
<!-- <dynamics damping="2.0" friction="1.0"/> -->
</joint>
<xacro:simple_gz_gripper_ros2_control prefix="${prefix}"/>
</xacro:macro>
</robot>