Reputation: 127
I am trying to write a URDF file for a simple pendulum that will act as a 'paddle' - i.e. upon collision with a bouncy ball, the ball will bounce off (like a volleyball player passing a volleyball).
Inspired by this bouncy ball example, I have written the URDF file given below, but loading it with parser.AddModelFromFile("filename.urdf")
gives this error:
RuntimeError: filename.urdf:39: error: Unable to read the 'value' attribute for the <drake:hunt_crossley_dissipation> tag
I am surprised that this doesn't work, since it was adapted from the bouncing ball example (which does work). I would really appreciate any guidance, thanks!
URDF file:
<?xml version="1.0"?>
<robot name="pendulum-paddle">
<material name="black">
<color rgba="0 0 0 1" />
</material>
<link name="base">
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
</link>
<joint name="base_weld" type="fixed">
<parent link="world" />
<child link="base" />
</joint>
<link name="arm">
<inertial>
<origin xyz="0 0 -1" rpy="0 0 0" />
<mass value="1" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin xyz="0 0 -.5" rpy="0 0 0" />
<geometry>
<box size="0.2 0.2 1"/>
</geometry>
<material name="black" />
</visual>
<collision name="collision">
<origin xyz="0 0 -.5" rpy="0 0 0" />
<geometry>
<box size="0.2 0.2 1"/>
</geometry>
<drake:proximity_properties>
<drake:hunt_crossley_dissipation>
0.1
</drake:hunt_crossley_dissipation>
<drake:point_contact_stiffness>
1000000
</drake:point_contact_stiffness>
</drake:proximity_properties>
</collision>
</link>
<joint name="shoulder" type="continuous">
<parent link="base"/>
<child link="arm" />
<axis xyz="0 1 0" />
</joint>
<transmission type="SimpleTransmission" name="shoulder_trans">
<actuator name="shoulder" />
<joint name="shoulder" />
<mechanicalReduction>1</mechanicalReduction>
</transmission>
</robot>
Upvotes: 0
Views: 52
Reputation: 5523
Unfortunately, the syntax is URDF is different than in SDF, and we tried to make the Drake tags comply to the standard. https://drake.mit.edu/doxygen_cxx/group__multibody__parsing.html#tag_drake_hunt_crossley_dissipation
In urdf, the proximity properties look more like:
<drake:proximity_properties>
<drake:mu_static value="0.8"/>
<drake:mu_dynamic value="0.3"/>
</drake:proximity_properties>
so try
<drake:proximity_properties>
<drake:hunt_crossley_dissipation value="0.1"/>
<drake:point_contact_stiffness value="1000000"/>
</drake:proximity_properties>
Upvotes: 2