Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Gazebo package #223

Merged
merged 17 commits into from Jan 27, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
84 changes: 79 additions & 5 deletions nextage_description/urdf/NextageOpen.urdf
Expand Up @@ -11,7 +11,37 @@
xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics">
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"
xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find nextage_description)/urdf/materials.urdf.xacro" />

<xacro:macro name="gazebo_nx_link" params="name color">
<gazebo reference="gazebo_${name}">
<material>Gazebo/${color}</material>
</gazebo>
</xacro:macro>

<xacro:macro name="transmission_nx_joint" params="name">
<transmission name="${name}_Trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_Motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>

<!-- Used for fixing robot to Gazebo 'base_link' -->
<link name="world"/>
<joint name="fixed" type="fixed">
<parent link="world"/>
<child link="WAIST"/>
</joint>

<xacro:gazebo_nx_link name="WAIST" color="Black" />
<link name="WAIST">
<visual>
<origin xyz="0 0 0.97" rpy="0 -0 0"/>
Expand All @@ -26,11 +56,13 @@
</geometry>
</collision>
<inertial>
<mass value="0" />
<mass value="30.0" />
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="0.0347318" ixy="5.78001e-06" ixz="-3.34135e-05" iyy="0.0347482" iyz="6.35727e-07" izz="0.00438238"/>
</inertial>
</link>

<xacro:gazebo_nx_link name="CHEST_JOINT0_Link" color="Black" />
<link name="CHEST_JOINT0_Link">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
Expand All @@ -45,11 +77,13 @@
</geometry>
</collision>
<inertial>
<mass value="0" />
<mass value="3.0" />
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="0.0639575" ixy="-0.00022833" ixz="0.00011172" iyy="0.0310845" iyz="6.48e-05" izz="0.0501107"/>
</inertial>
</link>

<xacro:gazebo_nx_link name="HEAD_JOINT0_Link" color="Black" />
<link name="HEAD_JOINT0_Link">
<visual>
<origin xyz="0 0 0.5695" rpy="0 -0 0"/>
Expand All @@ -69,6 +103,8 @@
<inertia ixx="0.00027682" ixy="3e-08" ixz="-3.3e-07" iyy="0.00013009" iyz="-1.092e-05" izz="0.00020954"/>
</inertial>
</link>

<xacro:gazebo_nx_link name="HEAD_JOINT1_Link" color="Black" />
<link name="HEAD_JOINT1_Link">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
Expand All @@ -84,10 +120,13 @@
</collision>
<inertial>
<mass value="0.0808593" />
<origin xyz="5.02e-06 -0.0166777 0.0163153" rpy="0 -0 0"/>
<inertia ixx="8.07e-05" ixy="-3e-08" ixz="-4.30134e-22" iyy="3.025e-05" iyz="-1.277e-05" izz="6.637e-05"/>
<!-- <origin xyz="5.02e-06 -0.0166777 0.0163153" rpy="0 -0 0"/> -->
<!-- <inertia ixx="8.07e-05" ixy="-3e-08" ixz="-4.30134e-22" iyy="3.025e-05" iyz="-1.277e-05" izz="6.637e-05"/> -->
<inertia ixx="1e-3" ixy="0" ixz="0" iyy="1e-3" iyz="0" izz="1e-3"/>
</inertial>
</link>

<xacro:gazebo_nx_link name="LARM_JOINT0_Link" color="Black" />
<link name="LARM_JOINT0_Link">
<visual>
<origin xyz="0 0.145 0.370296" rpy="-0.261799 0 0"/>
Expand All @@ -107,6 +146,7 @@
<inertia ixx="0.00207537" ixy="0.00011276" ixz="8.927e-05" iyy="0.00240295" iyz="-4.57e-05" izz="0.00141912"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="LARM_JOINT1_Link" color="Black" />
<link name="LARM_JOINT1_Link">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
Expand All @@ -126,6 +166,7 @@
<inertia ixx="0.0154168" ixy="9.95417e-07" ixz="3.38147e-06" iyy="0.0147117" iyz="0.00213719" izz="0.0012658"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="LARM_JOINT2_Link" color="Black" />
<link name="LARM_JOINT2_Link">
<visual>
<origin xyz="0 0.095 -0.25" rpy="0 -0 0"/>
Expand All @@ -145,6 +186,7 @@
<inertia ixx="0.00143966" ixy="-3e-07" ixz="1.2e-06" iyy="0.00141763" iyz="-7.596e-05" izz="0.0001972"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="LARM_JOINT3_Link" color="Black" />
<link name="LARM_JOINT3_Link">
<visual>
<origin xyz="-0.03 0 0" rpy="0 -0 0"/>
Expand All @@ -164,6 +206,7 @@
<inertia ixx="0.00069205" ixy="3e-08" ixz="5.2e-07" iyy="0.00068903" iyz="-1.915e-05" izz="0.00013509"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="LARM_JOINT4_Link" color="Black" />
<link name="LARM_JOINT4_Link">
<visual>
<origin xyz="0 0 -0.235" rpy="0 -0 0"/>
Expand All @@ -183,6 +226,7 @@
<inertia ixx="0.00052016" ixy="1.69e-06" ixz="7.9e-06" iyy="0.00050569" iyz="-5.377e-05" izz="0.00014004"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="LARM_JOINT5_Link" color="Black" />
<link name="LARM_JOINT5_Link">
<visual>
<origin xyz="-0.047 0 -0.09" rpy="0 -0 0"/>
Expand All @@ -202,6 +246,7 @@
<inertia ixx="0.00194072" ixy="1.1e-07" ixz="-0.00042482" iyy="0.00209392" iyz="1.2e-07" izz="0.00035788"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="RARM_JOINT0_Link" color="Black" />
<link name="RARM_JOINT0_Link">
<visual>
<origin xyz="0 -0.145 0.370296" rpy="0.261799 -0 0"/>
Expand All @@ -221,6 +266,7 @@
<inertia ixx="0.00207537" ixy="-0.00011276" ixz="8.927e-05" iyy="0.00240295" iyz="4.57e-05" izz="0.00141912"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="RARM_JOINT1_Link" color="Black" />
<link name="RARM_JOINT1_Link">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
Expand All @@ -240,6 +286,7 @@
<inertia ixx="0.0154168" ixy="-9.95417e-07" ixz="3.38147e-06" iyy="0.0147117" iyz="-0.00213719" izz="0.0012658"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="RARM_JOINT2_Link" color="Black" />
<link name="RARM_JOINT2_Link">
<visual>
<origin xyz="0 -0.095 -0.25" rpy="0 -0 0"/>
Expand All @@ -259,6 +306,7 @@
<inertia ixx="0.00143966" ixy="3e-07" ixz="1.2e-06" iyy="0.00141763" iyz="7.596e-05" izz="0.0001972"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="RARM_JOINT4_Link" color="Black" />
<link name="RARM_JOINT3_Link">
<visual>
<origin xyz="-0.03 0 0" rpy="0 -0 0"/>
Expand All @@ -278,6 +326,7 @@
<inertia ixx="0.00069205" ixy="-3e-08" ixz="5.2e-07" iyy="0.00068903" iyz="1.915e-05" izz="0.00013509"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="RARM_JOINT4_Link" color="Black" />
<link name="RARM_JOINT4_Link">
<visual>
<origin xyz="0 0 -0.235" rpy="0 -0 0"/>
Expand All @@ -297,6 +346,7 @@
<inertia ixx="0.00052016" ixy="-1.69e-06" ixz="7.9e-06" iyy="0.00050569" iyz="5.377e-05" izz="0.00014004"/>
</inertial>
</link>
<xacro:gazebo_nx_link name="RARM_JOINT5_Link" color="Black" />
<link name="RARM_JOINT5_Link">
<visual>
<origin xyz="-0.047 0 -0.09" rpy="0 -0 0"/>
Expand All @@ -316,6 +366,7 @@
<inertia ixx="0.00194072" ixy="-1.1e-07" ixz="-0.00042482" iyy="0.00209392" iyz="-1.2e-07" izz="0.00035788"/>
</inertial>
</link>
<xacro:transmission_nx_joint name="CHEST_JOINT0" />
<joint name="CHEST_JOINT0" type="revolute">
<parent link="WAIST"/>
<child link="CHEST_JOINT0_Link"/>
Expand All @@ -324,6 +375,7 @@
<limit lower="-2.84489" upper="2.84489" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="HEAD_JOINT0" />
<joint name="HEAD_JOINT0" type="revolute">
<parent link="CHEST_JOINT0_Link"/>
<child link="HEAD_JOINT0_Link"/>
Expand All @@ -332,6 +384,7 @@
<limit lower="-1.22173" upper="1.22173" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="HEAD_JOINT1" />
<joint name="HEAD_JOINT1" type="revolute">
<parent link="HEAD_JOINT0_Link"/>
<child link="HEAD_JOINT1_Link"/>
Expand All @@ -340,6 +393,7 @@
<limit lower="-0.349066" upper="1.22173" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="LARM_JOINT0" />
<joint name="LARM_JOINT0" type="revolute">
<parent link="CHEST_JOINT0_Link"/>
<child link="LARM_JOINT0_Link"/>
Expand All @@ -348,6 +402,7 @@
<limit lower="-1.53589" upper="1.53589" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="LARM_JOINT1" />
<joint name="LARM_JOINT1" type="revolute">
<parent link="LARM_JOINT0_Link"/>
<child link="LARM_JOINT1_Link"/>
Expand All @@ -356,6 +411,7 @@
<limit lower="-2.44346" upper="1.0472" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="LARM_JOINT2" />
<joint name="LARM_JOINT2" type="revolute">
<parent link="LARM_JOINT1_Link"/>
<child link="LARM_JOINT2_Link"/>
Expand All @@ -364,6 +420,7 @@
<limit lower="-2.75762" upper="0" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="LARM_JOINT3" />
<joint name="LARM_JOINT3" type="revolute">
<parent link="LARM_JOINT2_Link"/>
<child link="LARM_JOINT3_Link"/>
Expand All @@ -372,6 +429,7 @@
<limit lower="-1.8326" upper="2.87979" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="LARM_JOINT4" />
<joint name="LARM_JOINT4" type="revolute">
<parent link="LARM_JOINT3_Link"/>
<child link="LARM_JOINT4_Link"/>
Expand All @@ -380,6 +438,7 @@
<limit lower="-1.74533" upper="1.74533" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="LARM_JOINT5" />
<joint name="LARM_JOINT5" type="revolute">
<parent link="LARM_JOINT4_Link"/>
<child link="LARM_JOINT5_Link"/>
Expand All @@ -388,6 +447,7 @@
<limit lower="-2.84489" upper="2.84489" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="RARM_JOINT0" />
<joint name="RARM_JOINT0" type="revolute">
<parent link="CHEST_JOINT0_Link"/>
<child link="RARM_JOINT0_Link"/>
Expand All @@ -396,6 +456,7 @@
<limit lower="-1.53589" upper="1.53589" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="RARM_JOINT1" />
<joint name="RARM_JOINT1" type="revolute">
<parent link="RARM_JOINT0_Link"/>
<child link="RARM_JOINT1_Link"/>
Expand All @@ -404,6 +465,7 @@
<limit lower="-2.44346" upper="1.0472" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="RARM_JOINT2" />
<joint name="RARM_JOINT2" type="revolute">
<parent link="RARM_JOINT1_Link"/>
<child link="RARM_JOINT2_Link"/>
Expand All @@ -412,6 +474,7 @@
<limit lower="-2.75762" upper="0" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="RARM_JOINT3" />
<joint name="RARM_JOINT3" type="revolute">
<parent link="RARM_JOINT2_Link"/>
<child link="RARM_JOINT3_Link"/>
Expand All @@ -420,6 +483,7 @@
<limit lower="-2.87979" upper="1.8326" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="RARM_JOINT4" />
<joint name="RARM_JOINT4" type="revolute">
<parent link="RARM_JOINT3_Link"/>
<child link="RARM_JOINT4_Link"/>
Expand All @@ -428,6 +492,7 @@
<limit lower="-1.74533" upper="1.74533" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>
<xacro:transmission_nx_joint name="RARM_JOINT5" />
<joint name="RARM_JOINT5" type="revolute">
<parent link="RARM_JOINT4_Link"/>
<child link="RARM_JOINT5_Link"/>
Expand All @@ -436,4 +501,13 @@
<limit lower="-2.84489" upper="2.84489" effort="100" velocity="0.5" />
<dynamics damping="0.2" friction="0" />
</joint>

<!-- Gazebo plugin for ROS Control -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/NextageOpen</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>

</robot>
36 changes: 36 additions & 0 deletions nextage_description/urdf/materials.urdf.xacro
@@ -0,0 +1,36 @@
<?xml version="1.0"?>
<robot>

<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>

<material name="Blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>

<material name="Green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>

<material name="LightGrey">
<color rgba="0.6 0.6 0.6 1.0"/>
</material>

<material name="Grey">
<color rgba="0.4 0.4 0.4 1.0"/>
</material>

<material name="DarkGrey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>

<material name="Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>

<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>

</robot>