GCS_MAVLink: merge mavlink-solo

This commit is contained in:
Jonathan Challinger 2015-12-29 21:15:47 -08:00 committed by Andrew Tridgell
parent 41c881cc9e
commit c2b4235662
1 changed files with 768 additions and 1 deletions

View File

@ -49,6 +49,51 @@
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_POWER_OFF_INITIATED" value="42000">
<description>A system wide power-off event has been initiated.</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<!-- MAV_CMD_SOLO_BTN_* are here to provide vendor-specific support for 3DR Solo until a better solution is found to atomically make multiple commands with control flow -->
<entry name="MAV_CMD_SOLO_BTN_FLY_CLICK" value="42001">
<description>FLY button has been clicked.</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_SOLO_BTN_FLY_HOLD" value="42002">
<description>FLY button has been held for 1.5 seconds.</description>
<param index="1">Takeoff altitude</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_SOLO_BTN_PAUSE_CLICK" value="42003">
<description>PAUSE button has been clicked.</description>
<param index="1">1 if Solo is in a shot mode, 0 otherwise</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_START_MAG_CAL" value="42424">
<description>Initiate a magnetometer calibration</description>
<param index="1">uint8_t bitmask of magnetometers (0 means all)</param>
@ -92,6 +137,61 @@
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_GIMBAL_RESET" value="42501">
<description>Causes the gimbal to reset and boot as if it was just powered on</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_SET_FACTORY_TEST_MODE" value="42427">
<description>Command autopilot to get into factory test/diagnostic mode</description>
<param index="1">0 means get out of test mode, 1 means get into test mode</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS" value="42502">
<description>Reports progress and success or failure of gimbal axis calibration procedure</description>
<param index="1">Gimbal axis we're reporting calibration progress for</param>
<param index="2">Current calibration progress for this axis, 0x64=100%</param>
<param index="3">Status of the calibration</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION" value="42503">
<description>Starts commutation calibration on the gimbal</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_GIMBAL_FULL_RESET" value="42505">
<description>Erases gimbal application and parameters</description>
<param index="1">Magic number</param>
<param index="2">Magic number</param>
<param index="3">Magic number</param>
<param index="4">Magic number</param>
<param index="5">Magic number</param>
<param index="6">Magic number</param>
<param index="7">Magic number</param>
</entry>
</enum>
<!-- AP_Limits Enums -->
@ -244,6 +344,603 @@
</entry>
</enum>
<!-- Gimbal payload enumerations -->
<enum name="MAV_MODE_GIMBAL">
<entry name="MAV_MODE_GIMBAL_UNINITIALIZED" value="0">
<description>Gimbal is powered on but has not started initializing yet</description>
</entry>
<entry name="MAV_MODE_GIMBAL_CALIBRATING_PITCH" value="1">
<description>Gimbal is currently running calibration on the pitch axis</description>
</entry>
<entry name="MAV_MODE_GIMBAL_CALIBRATING_ROLL" value="2">
<description>Gimbal is currently running calibration on the roll axis</description>
</entry>
<entry name="MAV_MODE_GIMBAL_CALIBRATING_YAW" value="3">
<description>Gimbal is currently running calibration on the yaw axis</description>
</entry>
<entry name="MAV_MODE_GIMBAL_INITIALIZED" value="4">
<description>Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter</description>
</entry>
<entry name="MAV_MODE_GIMBAL_ACTIVE" value="5">
<description>Gimbal is actively stabilizing</description>
</entry>
<entry name="MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT" value="6">
<description>Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command</description>
</entry>
</enum>
<enum name="GIMBAL_AXIS">
<entry name="GIMBAL_AXIS_YAW" value="0">
<description>Gimbal yaw axis</description>
</entry>
<entry name="GIMBAL_AXIS_PITCH" value="1">
<description>Gimbal pitch axis</description>
</entry>
<entry name="GIMBAL_AXIS_ROLL" value="2">
<description>Gimbal roll axis</description>
</entry>
</enum>
<enum name="GIMBAL_AXIS_CALIBRATION_STATUS">
<entry name="GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS" value="0">
<description>Axis calibration is in progress</description>
</entry>
<entry name="GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED" value="1">
<description>Axis calibration succeeded</description>
</entry>
<entry name="GIMBAL_AXIS_CALIBRATION_STATUS_FAILED" value="2">
<description>Axis calibration failed</description>
</entry>
</enum>
<enum name="GIMBAL_AXIS_CALIBRATION_REQUIRED">
<entry name="GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN" value="0">
<description>Whether or not this axis requires calibration is unknown at this time</description>
</entry>
<entry name="GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE" value="1">
<description>This axis requires calibration</description>
</entry>
<entry name="GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE" value="2">
<description>This axis does not require calibration</description>
</entry>
</enum>
<!-- GoPro System Enumerations -->
<enum name="GOPRO_HEARTBEAT_STATUS">
<entry name="GOPRO_HEARTBEAT_STATUS_DISCONNECTED" value="0">
<description>No GoPro connected</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE" value="1">
<description>The detected GoPro is not HeroBus compatible</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_CONNECTED" value="2">
<description>A HeroBus compatible GoPro is connected</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_ERROR" value="3">
<description>An unrecoverable error was encountered with the connected GoPro, it may require a power cycle</description>
</entry>
</enum>
<enum name="GOPRO_HEARTBEAT_FLAGS">
<!-- each entry is a mask to test a bit in GOPRO_HEARTBEAT_STATUS.flags -->
<entry name="GOPRO_FLAG_RECORDING" value="1">
<description>GoPro is currently recording</description>
</entry>
</enum>
<enum name="GOPRO_REQUEST_STATUS">
<entry name="GOPRO_REQUEST_SUCCESS" value="0">
<description>The write message with ID indicated succeeded</description>
</entry>
<entry name="GOPRO_REQUEST_FAILED" value="1">
<description>The write message with ID indicated failed</description>
</entry>
</enum>
<enum name="GOPRO_COMMAND">
<entry name="GOPRO_COMMAND_POWER" value="0">
<description>(Get/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_CAPTURE_MODE" value="1">
<description>(Get/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_SHUTTER" value="2">
<description>(___/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_BATTERY" value="3">
<description>(Get/___)</description>
</entry>
<entry name="GOPRO_COMMAND_MODEL" value="4">
<description>(Get/___)</description>
</entry>
<entry name="GOPRO_COMMAND_VIDEO_SETTINGS" value="5">
<description>(Get/Set)</description>
<!-- Packet structure for the four values is as follows byte 0: GOPRO_RESOLUTION byte 1: GOPRO_FRAME_RATE byte 2: GOPRO_FIELD_OF_VIEW byte 3: GOPRO_VIDEO_SETTINGS_FLAGS -->
</entry>
<entry name="GOPRO_COMMAND_LOW_LIGHT" value="6">
<description>(Get/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_PHOTO_RESOLUTION" value="7">
<description>(Get/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_PHOTO_BURST_RATE" value="8">
<description>(Get/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_PROTUNE" value="9">
<description>(Get/Set)</description>
</entry>
<entry name="GOPRO_COMMAND_PROTUNE_WHITE_BALANCE" value="10">
<description>(Get/Set) Hero 3+ Only</description>
</entry>
<entry name="GOPRO_COMMAND_PROTUNE_COLOUR" value="11">
<description>(Get/Set) Hero 3+ Only</description>
</entry>
<entry name="GOPRO_COMMAND_PROTUNE_GAIN" value="12">
<description>(Get/Set) Hero 3+ Only</description>
</entry>
<entry name="GOPRO_COMMAND_PROTUNE_SHARPNESS" value="13">
<description>(Get/Set) Hero 3+ Only</description>
</entry>
<entry name="GOPRO_COMMAND_PROTUNE_EXPOSURE" value="14">
<description>(Get/Set) Hero 3+ Only</description>
</entry>
<entry name="GOPRO_COMMAND_TIME" value="15">
<description>(Get/Set)</description>
<!-- Packet structure for the four values is as follows byte 0...3: uint32_t unix timestamp (byte 0 is MSB) -->
</entry>
<entry name="GOPRO_COMMAND_CHARGING" value="16">
<description>(Get/Set)</description>
</entry>
</enum>
<enum name="GOPRO_CAPTURE_MODE">
<entry name="GOPRO_CAPTURE_MODE_VIDEO" value="0">
<description>Video mode</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_PHOTO" value="1">
<description>Photo mode</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_BURST" value="2">
<description>Burst mode, hero 3+ only</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_TIME_LAPSE" value="3">
<description>Time lapse mode, hero 3+ only</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_MULTI_SHOT" value="4">
<description>Multi shot mode, hero 4 only</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_PLAYBACK" value="5">
<description>Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_SETUP" value="6">
<description>Playback mode, hero 4 only</description>
</entry>
<entry name="GOPRO_CAPTURE_MODE_UNKNOWN" value="255">
<description>Mode not yet known</description>
</entry>
</enum>
<enum name="GOPRO_RESOLUTION">
<entry name="GOPRO_RESOLUTION_480p" value="0">
<description>848 x 480 (480p)</description>
</entry>
<entry name="GOPRO_RESOLUTION_720p" value="1">
<description>1280 x 720 (720p)</description>
</entry>
<entry name="GOPRO_RESOLUTION_960p" value="2">
<description>1280 x 960 (960p)</description>
</entry>
<entry name="GOPRO_RESOLUTION_1080p" value="3">
<description>1920 x 1080 (1080p)</description>
</entry>
<entry name="GOPRO_RESOLUTION_1440p" value="4">
<description>1920 x 1440 (1440p)</description>
</entry>
<entry name="GOPRO_RESOLUTION_2_7k_17_9" value="5">
<description>2704 x 1440 (2.7k-17:9)</description>
</entry>
<entry name="GOPRO_RESOLUTION_2_7k_16_9" value="6">
<description>2704 x 1524 (2.7k-16:9)</description>
</entry>
<entry name="GOPRO_RESOLUTION_2_7k_4_3" value="7">
<description>2704 x 2028 (2.7k-4:3)</description>
</entry>
<entry name="GOPRO_RESOLUTION_4k_16_9" value="8">
<description>3840 x 2160 (4k-16:9)</description>
</entry>
<entry name="GOPRO_RESOLUTION_4k_17_9" value="9">
<description>4096 x 2160 (4k-17:9)</description>
</entry>
<entry name="GOPRO_RESOLUTION_720p_SUPERVIEW" value="10">
<description>1280 x 720 (720p-SuperView)</description>
</entry>
<entry name="GOPRO_RESOLUTION_1080p_SUPERVIEW" value="11">
<description>1920 x 1080 (1080p-SuperView)</description>
</entry>
<entry name="GOPRO_RESOLUTION_2_7k_SUPERVIEW" value="12">
<description>2704 x 1520 (2.7k-SuperView)</description>
</entry>
<entry name="GOPRO_RESOLUTION_4k_SUPERVIEW" value="13">
<description>3840 x 2160 (4k-SuperView)</description>
</entry>
</enum>
<enum name="GOPRO_FRAME_RATE">
<entry name="GOPRO_FRAME_RATE_12" value="0">
<description>12 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_15" value="1">
<description>15 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_24" value="2">
<description>24 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_25" value="3">
<description>25 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_30" value="4">
<description>30 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_48" value="5">
<description>48 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_50" value="6">
<description>50 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_60" value="7">
<description>60 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_80" value="8">
<description>80 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_90" value="9">
<description>90 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_100" value="10">
<description>100 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_120" value="11">
<description>120 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_240" value="12">
<description>240 FPS</description>
</entry>
<entry name="GOPRO_FRAME_RATE_12_5" value="13">
<description>12.5 FPS</description>
</entry>
</enum>
<enum name="GOPRO_FIELD_OF_VIEW">
<entry name="GOPRO_FIELD_OF_VIEW_WIDE" value="0">
<description>0x00: Wide</description>
</entry>
<entry name="GOPRO_FIELD_OF_VIEW_MEDIUM" value="1">
<description>0x01: Medium</description>
</entry>
<entry name="GOPRO_FIELD_OF_VIEW_NARROW" value="2">
<description>0x02: Narrow</description>
</entry>
</enum>
<enum name="GOPRO_VIDEO_SETTINGS_FLAGS">
<entry name="GOPRO_VIDEO_SETTINGS_TV_MODE" value="1">
<description>0=NTSC, 1=PAL</description>
</entry>
</enum>
<enum name="GOPRO_PHOTO_RESOLUTION">
<entry name="GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM" value="0">
<description>5MP Medium</description>
</entry>
<entry name="GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM" value="1">
<description>7MP Medium</description>
</entry>
<entry name="GOPRO_PHOTO_RESOLUTION_7MP_WIDE" value="2">
<description>7MP Wide</description>
</entry>
<entry name="GOPRO_PHOTO_RESOLUTION_10MP_WIDE" value="3">
<description>10MP Wide</description>
</entry>
<entry name="GOPRO_PHOTO_RESOLUTION_12MP_WIDE" value="4">
<description>12MP Wide</description>
</entry>
</enum>
<enum name="GOPRO_PROTUNE_WHITE_BALANCE">
<entry name="GOPRO_PROTUNE_WHITE_BALANCE_AUTO" value="0">
<description>Auto</description>
</entry>
<entry name="GOPRO_PROTUNE_WHITE_BALANCE_3000K" value="1">
<description>3000K</description>
</entry>
<entry name="GOPRO_PROTUNE_WHITE_BALANCE_5500K" value="2">
<description>5500K</description>
</entry>
<entry name="GOPRO_PROTUNE_WHITE_BALANCE_6500K" value="3">
<description>6500K</description>
</entry>
<entry name="GOPRO_PROTUNE_WHITE_BALANCE_RAW" value="4">
<description>Camera Raw</description>
</entry>
</enum>
<enum name="GOPRO_PROTUNE_COLOUR">
<entry name="GOPRO_PROTUNE_COLOUR_STANDARD" value="0">
<description>Auto</description>
</entry>
<entry name="GOPRO_PROTUNE_COLOUR_NEUTRAL" value="1">
<description>Neutral</description>
</entry>
</enum>
<enum name="GOPRO_PROTUNE_GAIN">
<entry name="GOPRO_PROTUNE_GAIN_400" value="0">
<description>ISO 400</description>
</entry>
<entry name="GOPRO_PROTUNE_GAIN_800" value="1">
<description>ISO 800 (Only Hero 4)</description>
</entry>
<entry name="GOPRO_PROTUNE_GAIN_1600" value="2">
<description>ISO 1600</description>
</entry>
<entry name="GOPRO_PROTUNE_GAIN_3200" value="3">
<description>ISO 3200 (Only Hero 4)</description>
</entry>
<entry name="GOPRO_PROTUNE_GAIN_6400" value="4">
<description>ISO 6400</description>
</entry>
</enum>
<enum name="GOPRO_PROTUNE_SHARPNESS">
<entry name="GOPRO_PROTUNE_SHARPNESS_LOW" value="0">
<description>Low Sharpness</description>
</entry>
<entry name="GOPRO_PROTUNE_SHARPNESS_MEDIUM" value="1">
<description>Medium Sharpness</description>
</entry>
<entry name="GOPRO_PROTUNE_SHARPNESS_HIGH" value="2">
<description>High Sharpness</description>
</entry>
</enum>
<enum name="GOPRO_PROTUNE_EXPOSURE">
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_5_0" value="0">
<description>-5.0 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_4_5" value="1">
<description>-4.5 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_4_0" value="2">
<description>-4.0 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_3_5" value="3">
<description>-3.5 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_3_0" value="4">
<description>-3.0 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_2_5" value="5">
<description>-2.5 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_2_0" value="6">
<description>-2.0 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_1_5" value="7">
<description>-1.5 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_1_0" value="8">
<description>-1.0 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_NEG_0_5" value="9">
<description>-0.5 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_ZERO" value="10">
<description>0.0 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_0_5" value="11">
<description>+0.5 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_1_0" value="12">
<description>+1.0 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_1_5" value="13">
<description>+1.5 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_2_0" value="14">
<description>+2.0 EV</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_2_5" value="15">
<description>+2.5 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_3_0" value="16">
<description>+3.0 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_3_5" value="17">
<description>+3.5 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_4_0" value="18">
<description>+4.0 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_4_5" value="19">
<description>+4.5 EV (Hero 3+ Only)</description>
</entry>
<entry name="GOPRO_PROTUNE_EXPOSURE_POS_5_0" value="20">
<description>+5.0 EV (Hero 3+ Only)</description>
</entry>
</enum>
<enum name="GOPRO_CHARGING">
<entry name="GOPRO_CHARGING_DISABLED" value="0">
<description>Charging disabled</description>
</entry>
<entry name="GOPRO_CHARGING_ENABLED" value="1">
<description>Charging enabled</description>
</entry>
</enum>
<enum name="GOPRO_MODEL">
<entry name="GOPRO_MODEL_UNKNOWN" value="0">
<description>Unknown gopro model</description>
</entry>
<entry name="GOPRO_MODEL_HERO_3_PLUS_SILVER" value="1">
<description>Hero 3+ Silver (HeroBus not supported by GoPro)</description>
</entry>
<entry name="GOPRO_MODEL_HERO_3_PLUS_BLACK" value="2">
<description>Hero 3+ Black</description>
</entry>
<entry name="GOPRO_MODEL_HERO_4_SILVER" value="3">
<description>Hero 4 Silver</description>
</entry>
<entry name="GOPRO_MODEL_HERO_4_BLACK" value="4">
<description>Hero 4 Black</description>
</entry>
</enum>
<enum name="GOPRO_BURST_RATE">
<entry name="GOPRO_BURST_RATE_3_IN_1_SECOND" value="0">
<description>3 Shots / 1 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_5_IN_1_SECOND" value="1">
<description>5 Shots / 1 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_10_IN_1_SECOND" value="2">
<description>10 Shots / 1 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_10_IN_2_SECOND" value="3">
<description>10 Shots / 2 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_10_IN_3_SECOND" value="4">
<description>10 Shots / 3 Second (Hero 4 Only)</description>
</entry>
<entry name="GOPRO_BURST_RATE_30_IN_1_SECOND" value="5">
<description>30 Shots / 1 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_30_IN_2_SECOND" value="6">
<description>30 Shots / 2 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_30_IN_3_SECOND" value="7">
<description>30 Shots / 3 Second</description>
</entry>
<entry name="GOPRO_BURST_RATE_30_IN_6_SECOND" value="8">
<description>30 Shots / 6 Second</description>
</entry>
</enum>
<!-- led control pattern enums (enumeration of specific patterns) -->
<enum name="LED_CONTROL_PATTERN">
<entry name="LED_CONTROL_PATTERN_OFF" value="0">
@ -786,8 +1483,78 @@
<field name="D" type="float">D component</field>
</message>
<!-- 200 to 225 RESERVED for Solo stuff-->
<message id="200" name="GIMBAL_REPORT">
<description>3 axis gimbal mesuraments</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="delta_time" type="float">Time since last update (seconds)</field>
<field name="delta_angle_x" type="float">Delta angle X (radians)</field>
<field name="delta_angle_y" type="float">Delta angle Y (radians)</field>
<field name="delta_angle_z" type="float">Delta angle X (radians)</field>
<field name="delta_velocity_x" type="float">Delta velocity X (m/s)</field>
<field name="delta_velocity_y" type="float">Delta velocity Y (m/s)</field>
<field name="delta_velocity_z" type="float">Delta velocity Z (m/s)</field>
<field name="joint_roll" type="float">Joint ROLL (radians)</field>
<field name="joint_el" type="float">Joint EL (radians)</field>
<field name="joint_az" type="float">Joint AZ (radians)</field>
</message>
<message id="201" name="GIMBAL_CONTROL">
<description>Control message for rate gimbal</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="demanded_rate_x" type="float">Demanded angular rate X (rad/s)</field>
<field name="demanded_rate_y" type="float">Demanded angular rate Y (rad/s)</field>
<field name="demanded_rate_z" type="float">Demanded angular rate Z (rad/s)</field>
</message>
<message id="214" name="GIMBAL_TORQUE_CMD_REPORT">
<description>100 Hz gimbal torque command telemetry</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="rl_torque_cmd" type="int16_t">Roll Torque Command</field>
<field name="el_torque_cmd" type="int16_t">Elevation Torque Command</field>
<field name="az_torque_cmd" type="int16_t">Azimuth Torque Command</field>
</message>
<!-- GoPro Messages -->
<message id="215" name="GOPRO_HEARTBEAT">
<description>Heartbeat from a HeroBus attached GoPro</description>
<field enum="GOPRO_HEARTBEAT_STATUS" name="status" type="uint8_t">Status</field>
<field enum="GOPRO_CAPTURE_MODE" name="capture_mode" type="uint8_t">Current capture mode</field>
<field name="flags" type="uint8_t">additional status bits</field>
<!-- see GOPRO_HEARTBEAT_FLAGS -->
</message>
<message id="216" name="GOPRO_GET_REQUEST">
<description>Request a GOPRO_COMMAND response from the GoPro</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field enum="GOPRO_COMMAND" name="cmd_id" type="uint8_t">Command ID</field>
</message>
<message id="217" name="GOPRO_GET_RESPONSE">
<description>Response from a GOPRO_COMMAND get request</description>
<field enum="GOPRO_COMMAND" name="cmd_id" type="uint8_t">Command ID</field>
<field enum="GOPRO_REQUEST_STATUS" name="status" type="uint8_t">Status</field>
<field name="value" type="uint8_t[4]">Value</field>
</message>
<message id="218" name="GOPRO_SET_REQUEST">
<description>Request to set a GOPRO_COMMAND with a desired</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field enum="GOPRO_COMMAND" name="cmd_id" type="uint8_t">Command ID</field>
<field name="value" type="uint8_t[4]">Value</field>
</message>
<message id="219" name="GOPRO_SET_RESPONSE">
<description>Response from a GOPRO_COMMAND set request</description>
<field enum="GOPRO_COMMAND" name="cmd_id" type="uint8_t">Command ID</field>
<field enum="GOPRO_REQUEST_STATUS" name="status" type="uint8_t">Status</field>
</message>
<!-- 219 to 224 RESERVED for more GOPRO-->
<message id="226" name="RPM">
<description>RPM sensor output</description>
<field name="rpm1" type="float">RPM Sensor1</field>