Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#1078 from blandry/drakecfexample
Browse files Browse the repository at this point in the history
Simple example of using the crazyflie model with Drake
  • Loading branch information
RussTedrake committed May 4, 2015
2 parents 7623784 + 7e6e180 commit b4030cf
Show file tree
Hide file tree
Showing 5 changed files with 86,350 additions and 0 deletions.
71 changes: 71 additions & 0 deletions examples/Quadrotor/crazyflie/crazyflie.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
<?xml version="1.0" ?>
<robot xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
name="crazyflie">
<material name="Brown">
<color rgba="83./255. 53./255. 10./255."/>
</material>
<material name="White">
<color rgba="1 1 1"/>
</material>
<material name="Grey">
<color rgba=".3 .3 .3"/>
</material>
<material name="Red">
<color rgba="1 0 0"/>
</material>
<material name="Blue">
<color rgba="0 0 1"/>
</material>

<link name="base_link">
<inertial>
<mass value="0.03352"/>
<origin xyz="0 0 0"/>
<inertia ixx="2.3951e-05" ixy="0" ixz="0" iyy="2.3951e-05" iyz="0" izz="3.23466e-05"/>
</inertial>
<visual>
<origin rpy="1.570796326794897 0 -2.356194490192345" xyz="0 0 -.01"/>
<geometry>
<mesh filename="mesh/crazyflie.obj" scale=".001"/>
</geometry>
<material name="Blue"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.017 0.017 0.006"/>
</geometry>
</collision>
</link>

<force_element name="prop1">
<propellor lower_limit="2.8" upper_limit="40.87" scale_factor_thrust="0.005022393588278" scale_factor_moment="-1.858017992629931e-05" visual_geometry="false">
<parent link="base_link"/>
<origin xyz="0.046 0 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop2">
<propellor lower_limit="2.8" upper_limit="40.87" scale_factor_thrust="0.005022393588278" scale_factor_moment="1.858017992629931e-05" visual_geometry="false">
<parent link="base_link"/>
<origin xyz="0 -0.046 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop3">
<propellor lower_limit="2.8" upper_limit="40.87" scale_factor_thrust="0.005022393588278" scale_factor_moment="-1.858017992629931e-05" visual_geometry="false">
<parent link="base_link"/>
<origin xyz="-0.046 0 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop4">
<propellor lower_limit="2.8" upper_limit="40.87" scale_factor_thrust="0.005022393588278" scale_factor_moment="1.858017992629931e-05" visual_geometry="false">
<parent link="base_link"/>
<origin xyz="0 0.046 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>

</robot>
Loading

0 comments on commit b4030cf

Please sign in to comment.