ualberta.xml 3.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. <?xml version="1.0"?>
  2. <mavlink>
  3. <include>common.xml</include>
  4. <enums>
  5. <enum name="UALBERTA_AUTOPILOT_MODE">
  6. <description>Available autopilot modes for ualberta uav</description>
  7. <entry name="MODE_MANUAL_DIRECT">
  8. <description>Raw input pulse widts sent to output</description>
  9. </entry>
  10. <entry name="MODE_MANUAL_SCALED">
  11. <description>Inputs are normalized using calibration, the converted back to raw pulse widths for output</description>
  12. </entry>
  13. <entry name="MODE_AUTO_PID_ATT">
  14. <description> dfsdfs</description>
  15. </entry>
  16. <entry name="MODE_AUTO_PID_VEL">
  17. <description> dfsfds</description>
  18. </entry>
  19. <entry name="MODE_AUTO_PID_POS">
  20. <description> dfsdfsdfs</description>
  21. </entry>
  22. </enum>
  23. <enum name="UALBERTA_NAV_MODE">
  24. <description>Navigation filter mode</description>
  25. <entry name="NAV_AHRS_INIT"/>
  26. <entry name="NAV_AHRS">
  27. <description>AHRS mode</description>
  28. </entry>
  29. <entry name="NAV_INS_GPS_INIT">
  30. <description>INS/GPS initialization mode</description>
  31. </entry>
  32. <entry name="NAV_INS_GPS">
  33. <description>INS/GPS mode</description>
  34. </entry>
  35. </enum>
  36. <enum name="UALBERTA_PILOT_MODE">
  37. <description>Mode currently commanded by pilot</description>
  38. <entry name="PILOT_MANUAL">
  39. <description> sdf</description>
  40. </entry>
  41. <entry name="PILOT_AUTO">
  42. <description> dfs</description>
  43. </entry>
  44. <entry name="PILOT_ROTO">
  45. <description> Rotomotion mode </description>
  46. </entry>
  47. </enum>
  48. </enums>
  49. <messages>
  50. <message id="220" name="NAV_FILTER_BIAS">
  51. <description>Accelerometer and Gyro biases from the navigation filter</description>
  52. <field type="uint64_t" name="usec">Timestamp (microseconds)</field>
  53. <field type="float" name="accel_0">b_f[0]</field>
  54. <field type="float" name="accel_1">b_f[1]</field>
  55. <field type="float" name="accel_2">b_f[2]</field>
  56. <field type="float" name="gyro_0">b_f[0]</field>
  57. <field type="float" name="gyro_1">b_f[1]</field>
  58. <field type="float" name="gyro_2">b_f[2]</field>
  59. </message>
  60. <message id="221" name="RADIO_CALIBRATION">
  61. <description>Complete set of calibration parameters for the radio</description>
  62. <field type="uint16_t[3]" name="aileron">Aileron setpoints: left, center, right</field>
  63. <field type="uint16_t[3]" name="elevator">Elevator setpoints: nose down, center, nose up</field>
  64. <field type="uint16_t[3]" name="rudder">Rudder setpoints: nose left, center, nose right</field>
  65. <field type="uint16_t[2]" name="gyro">Tail gyro mode/gain setpoints: heading hold, rate mode</field>
  66. <field type="uint16_t[5]" name="pitch">Pitch curve setpoints (every 25%)</field>
  67. <field type="uint16_t[5]" name="throttle">Throttle curve setpoints (every 25%)</field>
  68. </message>
  69. <message id="222" name="UALBERTA_SYS_STATUS">
  70. <description>System status specific to ualberta uav</description>
  71. <field type="uint8_t" name="mode">System mode, see UALBERTA_AUTOPILOT_MODE ENUM</field>
  72. <field type="uint8_t" name="nav_mode">Navigation mode, see UALBERTA_NAV_MODE ENUM</field>
  73. <field type="uint8_t" name="pilot">Pilot mode, see UALBERTA_PILOT_MODE</field>
  74. </message>
  75. </messages>
  76. </mavlink>