-
Notifications
You must be signed in to change notification settings - Fork 95
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #167 from iirob/pw70_description
Pw70 description
- Loading branch information
Showing
6 changed files
with
232 additions
and
0 deletions.
There are no files selected for viewing
Binary file not shown.
Binary file not shown.
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,18 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
|
||
<xacro:macro name="schunk_pw70_gazebo" params="name"> | ||
|
||
<gazebo reference="${name}_pan_link"> | ||
<gravity>true</gravity> | ||
<self_collide>false</self_collide> | ||
</gazebo> | ||
|
||
<gazebo reference="${name}_tilt_link"> | ||
<gravity>true</gravity> | ||
<self_collide>false</self_collide> | ||
</gazebo> | ||
|
||
</xacro:macro> | ||
|
||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,34 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
|
||
<xacro:macro name="schunk_pg70_transmission" params="name"> | ||
|
||
<!-- finger1 --> | ||
<transmission name="${name}_pan_rotation"> | ||
<type>transmission_interface/SimpleTransmission</type> | ||
<joint name="${name}_pan_joint"> | ||
<hardwareInterface>PositionJointInterface</hardwareInterface> | ||
<hardwareInterface>VelocityJointInterface</hardwareInterface> | ||
<hardwareInterface>EffortJointInterface</hardwareInterface> | ||
</joint> | ||
<actuator name="${name}_pan_motor"> | ||
<mechanicalReduction>1</mechanicalReduction> | ||
</actuator> | ||
</transmission> | ||
|
||
<!-- finger2 - mimic --> | ||
<transmission name="${name}_tilt_rotation"> | ||
<type>transmission_interface/SimpleTransmission</type> | ||
<joint name="${name}_tilt_joint"> | ||
<hardwareInterface>PositionJointInterface</hardwareInterface> | ||
<hardwareInterface>VelocityJointInterface</hardwareInterface> | ||
<hardwareInterface>EffortJointInterface</hardwareInterface> | ||
</joint> | ||
<actuator name="${name}_tilt_motor"> | ||
<mechanicalReduction>1</mechanicalReduction> | ||
</actuator> | ||
</transmission> | ||
|
||
</xacro:macro> | ||
|
||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,180 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
|
||
<xacro:include filename="$(find schunk_description)/urdf/pw70/pw70.gazebo.xacro" /> | ||
<xacro:include filename="$(find schunk_description)/urdf/pw70/pw70.transmission.xacro" /> | ||
|
||
<xacro:macro name="schunk_pw70" params="parent name *origin is_upsidedown"> | ||
|
||
<xacro:unless value="${is_upsidedown}"> | ||
|
||
<joint name="${name}_joint" type="fixed" > | ||
<xacro:insert_block name="origin" /> | ||
<parent link="${parent}" /> | ||
<child link="${name}_link" /> | ||
</joint> | ||
|
||
<link name="${name}_link"> | ||
<xacro:default_inertial/> | ||
<visual> | ||
<origin xyz="0 0 0.07" rpy="0 0 0" /> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_square_holder.stl" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_square_holder.stl" /> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="${name}_tilt_joint" type="revolute" > | ||
<origin xyz="0 0 0.07" rpy="0 0 0"/> | ||
<parent link="${name}_link" /> | ||
<child link="${name}_tilt_link" /> | ||
<axis xyz="-1 0 0" /> | ||
<limit effort="12.0" velocity="4.1" lower="${-4/6 * M_PI}" upper="${4/6 * M_PI}"/> | ||
<calibration rising="0.0"/> | ||
</joint> | ||
|
||
<link name="${name}_tilt_link"> | ||
<xacro:default_inertial/> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="0 0 0" /> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_body.stl" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_body.stl" /> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="${name}_pan_joint" type="revolute" > | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<parent link="${name}_tilt_link" /> | ||
<child link="${name}_pan_link" /> | ||
<axis xyz="0 0 1" /> | ||
<limit effort="200" velocity="${2 * M_PI}" lower="${-7/3 * M_PI}" upper="${7/3 * M_PI}"/> | ||
<calibration rising="0.0"/> | ||
</joint> | ||
|
||
<link name="${name}_pan_link"> | ||
<xacro:default_inertial/> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="0 0 0" /> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_round_holder.stl" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_round_holder.stl" /> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="${name}_tool_joint" type="fixed" > | ||
<origin xyz="0 0 0.095" rpy="0 0 0"/> | ||
<parent link="${name}_pan_link" /> | ||
<child link="${name}_tool_link" /> | ||
</joint> | ||
|
||
<link name="${name}_tool_link"> | ||
<xacro:default_inertial/> | ||
</link> | ||
</xacro:unless> | ||
|
||
<xacro:if value="${is_upsidedown}"> | ||
|
||
<joint name="${name}_joint" type="fixed" > | ||
<xacro:insert_block name="origin" /> | ||
<parent link="${parent}" /> | ||
<child link="${name}_link" /> | ||
</joint> | ||
|
||
<link name="${name}_link"> | ||
<xacro:default_inertial/> | ||
<visual> | ||
<origin xyz="0 0 0.095" rpy="${M_PI} 0 0" /> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_round_holder.stl" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_round_holder.stl" /> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="${name}_pan_joint" type="revolute" > | ||
<origin xyz="0 0 0.095" rpy="0 0 0"/> | ||
<parent link="${name}_link" /> | ||
<child link="${name}_pan_link" /> | ||
<axis xyz="0 0 -1" /> | ||
<limit effort="200" velocity="${2 * M_PI}" lower="${-7/3 * M_PI}" upper="${7/3 * M_PI}"/> | ||
<calibration rising="0.0"/> | ||
</joint> | ||
|
||
<link name="${name}_pan_link"> | ||
<xacro:default_inertial/> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="${M_PI} 0 0" /> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_body.stl" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_body.stl"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="${name}_tilt_joint" type="revolute" > | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<parent link="${name}_pan_link" /> | ||
<child link="${name}_tilt_link" /> | ||
<axis xyz="-1 0 0" /> | ||
<limit effort="12.0" velocity="4.1" lower="${-4/6 * M_PI}" upper="${4/6 * M_PI}"/> | ||
<calibration rising="0.0"/> | ||
</joint> | ||
|
||
<link name="${name}_tilt_link"> | ||
<xacro:default_inertial/> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="${M_PI} 0 0" /> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_square_holder.stl" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://schunk_description/meshes/pw70/pw70_square_holder.stl" /> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<joint name="${name}_tool_joint" type="fixed" > | ||
<origin xyz="0 0 0.07" rpy="0 0 0"/> | ||
<parent link="${name}_tilt_link" /> | ||
<child link="${name}_tool_link" /> | ||
</joint> | ||
|
||
<link name="${name}_tool_link"> | ||
<xacro:default_inertial/> | ||
</link> | ||
</xacro:if> | ||
|
||
<!-- extensions --> | ||
<xacro:schunk_pw70_gazebo name="${name}" /> | ||
<xacro:schunk_pw70_transmission name="${name}" /> | ||
|
||
|
||
</xacro:macro> | ||
</robot> | ||
|