Skip to content
Closed
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
62 changes: 62 additions & 0 deletions ar4_description/config/link_properties.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -246,3 +246,65 @@ link_6:
dr: 0.0
dp: 0.0
dY: 0.0

gripper_base:
inertial:
size:
dx: 0.035
dy: 0.02
dz: 0.02
mass: 0.08
origin:
dx: 0.0
dy: -0.025
dz: 0.0
dr: 0.0
dp: 0.0
dY: 0.0
visual:
origin:
dx: 0.0
dy: 0.0
dz: 0.0
dr: 0.0
dp: 0.0
dY: 0.0
collision:
origin:
dx: 0.0
dy: 0.0
dz: 0.0
dr: 0.0
dp: 0.0
dY: 0.0

finger:
inertial:
size:
dx: 0.007
dy: 0.015
dz: 0.02
mass: 0.01
origin:
dx: -0.005
dy: -0.015
dz: 0.0
dr: 0.0
dp: 0.0
dY: 0.0
visual:
origin:
dx: 0.0
dy: 0.0
dz: 0.0
dr: 0.0
dp: 0.0
dY: 0.0
collision:
origin:
dx: 0.0
dy: 0.0
dz: 0.0
dr: 0.0
dp: 0.0
dY: 0.0
Binary file added ar4_description/meshes/gripper_base.stl
Binary file not shown.
Binary file added ar4_description/meshes/gripper_finger.stl
Binary file not shown.
27 changes: 27 additions & 0 deletions ar4_description/urdf/ar4.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -111,4 +111,31 @@
<axis xyz="0 0 1"/>
<limit lower="${-1.0 * robot_parameters['j6_limit']}" upper="${robot_parameters['j6_limit']}" effort="100" velocity="1.0"/>
</joint>

<xacro:gripper_base parent="link_6"
inertial="${robot_properties['gripper_base']['inertial']}"
visual="${robot_properties['gripper_base']['visual']}"
collision="${robot_properties['gripper_base']['collision']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:gripper_base>

<xacro:finger number="1"
pitch_rotation="0.0"
mimic="false"
inertial="${robot_properties['finger']['inertial']}"
visual="${robot_properties['finger']['visual']}"
collision="${robot_properties['finger']['collision']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:finger>

<xacro:finger number="2"
pitch_rotation="${-pi}"
mimic="true"
inertial="${robot_properties['finger']['inertial']}"
visual="${robot_properties['finger']['visual']}"
collision="${robot_properties['finger']['collision']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:finger>


</robot>
55 changes: 55 additions & 0 deletions ar4_description/urdf/include/common_macros.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,61 @@
</xacro:if>
</xacro:macro>

<!-- ===================== Gripper base xacro ================================== -->
<xacro:macro name="gripper_base" params="parent *origin inertial visual collision">

<joint name="gripper_base_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="${-pi/2} 0.0 ${pi}"/>
<parent link="${parent}"/>
<child link="gripper_base_link"/>
</joint>

<link name="gripper_base_link">
<xacro:insert_block name="origin"/>

<xacro:box_inertia m="${inertial['mass']}"
x="${inertial['size']['dx']}"
y="${inertial['size']['dy']}"
z="${inertial['size']['dz']}"
o_xyz="${inertial['origin']['dx']} ${inertial['origin']['dy']} ${inertial['origin']['dz']}"
o_rpy="${inertial['origin']['dr']} ${inertial['origin']['dp']} ${inertial['origin']['dY']}">
</xacro:box_inertia>

<xacro:mesh_loop meshes="${['gripper_base']}" materials="${['grey']}" visual="${visual}" collision="${collision}" />

</link>

</xacro:macro>

<!-- ===================== Gripper finger ================================== -->
<xacro:macro name="finger" params="number pitch_rotation mimic *origin inertial visual collision">

<joint name="finger_joint${number}" type="prismatic">
<origin xyz="0.0 -0.036 0" rpy="0.0 ${pitch_rotation} 0.0"/>
<parent link="gripper_base_link"/>
<child link="finger${number}"/>
<axis xyz="1 0 0"/>
<limit lower="-0.014" upper="0" effort="100" velocity="1.0"/>
<xacro:if value="${mimic == 'true'}">
<mimic joint="finger_joint1" multiplier="1" offset="0"/>
</xacro:if>
</joint>

<link name="finger${number}">
<xacro:insert_block name="origin"/>

<xacro:box_inertia m="${inertial['mass']}"
x="${inertial['size']['dx']}"
y="${inertial['size']['dy']}"
z="${inertial['size']['dz']}"
o_xyz="${inertial['origin']['dx']} ${inertial['origin']['dy']} ${inertial['origin']['dz']}"
o_rpy="${inertial['origin']['dr']} ${inertial['origin']['dp']} ${inertial['origin']['dY']}">
</xacro:box_inertia>

<xacro:mesh_loop meshes="${['gripper_finger']}" materials="${['black']}" visual="${visual}" collision="${collision}" />
</link>

</xacro:macro>


<!-- ===================== Box inertia xacro ================================== -->
Expand Down
Loading