Skip to content

Commit

Permalink
Cleans up Pendulum.urdf. (#5164)
Browse files Browse the repository at this point in the history
  • Loading branch information
Chien-Liang Fok authored Feb 14, 2017
1 parent 539e8e3 commit cf497e8
Showing 1 changed file with 43 additions and 46 deletions.
89 changes: 43 additions & 46 deletions drake/examples/Pendulum/Pendulum.urdf
Original file line number Diff line number Diff line change
@@ -1,74 +1,73 @@
<?xml version="1.0"?>

<robot xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="http://drake.mit.edu ../../doc/drakeURDF.xsd" name="Pendulum">
<robot name="Pendulum"
xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="http://drake.mit.edu ../../doc/drakeURDF.xsd">
<material name="green">
<color rgba=".3 .6 .4 1" />
<color rgba=".3 .6 .4 1"/>
</material>
<material name="red">
<color rgba=".9 .1 0 1" />
<color rgba=".9 .1 0 1"/>
</material>
<material name="blue">
<color rgba="0 0 1 1" />
<color rgba="0 0 1 1"/>
</material>


<link name="world" drake_ignore="true">
<inertial> <!-- drc-viewer needs this to have inertia to parse properly. remove it when that bug is fixed -->
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
<link drake_ignore="true" name="world">
<inertial>
<!-- drc-viewer needs this to have inertia to parse properly. Remove it when that bug is fixed. -->
<origin xyz="0 0 0"/>
<mass value="0.01"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<link name="base_part2">
<inertial>
<origin xyz="0 0 .015" rpy="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 .015"/>
<mass value="1"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin xyz="0 0 .015" />
<origin xyz="0 0 .015"/>
<geometry>
<sphere radius=".015" />
</geometry>
<material name="green" />
<sphere radius=".015"/>
</geometry>
<material name="green"/>
</visual>
</link>
<joint name="base_weld" type="fixed" drake_ignore="true">
<parent link="world" />
<child link="base_part2" />
<origin xyz="0 0 1" />
<joint drake_ignore="true" name="base_weld" type="fixed">
<parent link="world"/>
<child link="base_part2"/>
<origin xyz="0 0 1"/>
</joint>
<link name="arm">
<inertial>
<origin xyz="0 0 -.5" rpy="0 0 0" />
<mass value="0.5" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertial>
<origin rpy="0 0 0" xyz="0 0 -.5"/>
<mass value="0.5"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin xyz="0 0 -.375" rpy="0 0 0" />
<origin rpy="0 0 0" xyz="0 0 -.375"/>
<geometry>
<cylinder length=".75" radius=".01" />
<cylinder length=".75" radius=".01"/>
</geometry>
<material name="red" />
</visual>
<material name="red"/>
</visual>
<collision>
<origin xyz="0 0 -.375" rpy="0 0 0" />
<origin rpy="0 0 0" xyz="0 0 -.375"/>
<geometry>
<cylinder length=".75" radius=".01" />
<cylinder length=".75" radius=".01"/>
</geometry>
</collision>
</link>
<joint name="theta" type="continuous">
<parent link="base_part2"/>
<child link="arm" />
<axis xyz="0 1 0" />
<dynamics damping="0.1" />
<child link="arm"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.1"/>
</joint>
<link name="arm_com">
<inertial>
<origin xyz="0 0 -0.5" rpy="0 0 0" />
<origin rpy="0 0 0" xyz="0 0 -0.5"/>
<mass value="0.5"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
Expand All @@ -77,7 +76,7 @@
<geometry>
<sphere radius=".025"/>
</geometry>
<material name="blue" />
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 -.5"/>
Expand All @@ -87,13 +86,12 @@
</collision>
</link>
<joint name="arm_weld" type="fixed">
<parent link="arm" />
<child link="arm_com" />
<parent link="arm"/>
<child link="arm_com"/>
</joint>

<transmission type="SimpleTransmission" name="elbow_trans">
<actuator name="tau" />
<joint name="theta" />
<transmission name="elbow_trans" type="SimpleTransmission">
<actuator name="tau"/>
<joint name="theta"/>
<mechanicalReduction>1</mechanicalReduction>
</transmission>
<gazebo reference="base_part2">
Expand All @@ -105,7 +103,6 @@
<gazebo reference="arm_com">
<material>Gazebo/Blue</material>
</gazebo>

<gazebo>
<plugin filename="libgazebo_ros_pub_robot_state.so" name="gazebo_ros_pub_robot_controller">
<alwaysOn>true</alwaysOn>
Expand Down

0 comments on commit cf497e8

Please sign in to comment.