quadrotor.urdf 2.1 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162
  1. <?xml version="1.0" ?>
  2. <!-- adapted from Daniel Mellinger, Nathan Michael, Vijay Kumar, "Trajectory Generation and Control for Precise Aggressive Maneuvers with Quadrotors" -->
  3. <robot xmlns="http://drake.mit.edu"
  4. xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
  5. xsi:schemaLocation="http://drake.mit.edu ../../../../pods/drake/doc/drakeURDF.xsd" name="quadrotor">
  6. <link name="base_link">
  7. <inertial>
  8. <mass value="0.5"/>
  9. <origin xyz="0 0 0"/>
  10. <inertia ixx="0.0023" ixy="0.0" ixz="0.0" iyy="0.0023" iyz="0.0" izz="0.004"/>
  11. </inertial>
  12. <visual>
  13. <origin rpy="0 0 0" xyz="0 0 0"/>
  14. <geometry>
  15. <mesh filename="quadrotor_base.obj" scale=".1 .1 .1"/>
  16. </geometry>
  17. </visual>
  18. <!-- note: the original hector quadrotor urdf had a (simplified, but still complex) collision mesh, too -->
  19. <collision>
  20. <origin rpy="0 0 0" xyz="0 0 0"/>
  21. <geometry>
  22. <cylinder radius=".3" length=".1"/>
  23. </geometry>
  24. </collision>
  25. </link>
  26. <frame link="base_link" name="body" rpy="0 0 0" xyz="0 0 0" />
  27. <force_element name="prop1">
  28. <propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="0.0245">
  29. <parent link="base_link"/>
  30. <origin xyz=".1750 0 0"/>
  31. <axis xyz="0 0 1"/>
  32. </propellor>
  33. </force_element>
  34. <force_element name="prop2">
  35. <propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="-0.0245">
  36. <parent link="base_link"/>
  37. <origin xyz="0 .1750 0 "/>
  38. <axis xyz="0 0 1"/>
  39. </propellor>
  40. </force_element>
  41. <force_element name="prop3">
  42. <propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="0.0245">
  43. <parent link="base_link"/>
  44. <origin xyz="-.1750 0 0"/>
  45. <axis xyz="0 0 1"/>
  46. </propellor>
  47. </force_element>
  48. <force_element name="prop4">
  49. <propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="-0.0245">
  50. <parent link="base_link"/>
  51. <origin xyz="0 -.1750 0"/>
  52. <axis xyz="0 0 1"/>
  53. </propellor>
  54. </force_element>
  55. </robot>