ardupilot/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml

951 lines
57 KiB
XML

<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<!-- note that APM specific messages should use the command id
range from 150 to 250, to leave plenty of room for growth
of common.xml
If you prototype a message here, then you should consider if it
is general enough to move into common.xml later
-->
<enums>
<!-- ardupilot specific MAV_CMD_* commands -->
<enum name="MAV_CMD">
<entry name="MAV_CMD_DO_MOTOR_TEST" value="209">
<description>Mission command to perform motor test</description>
<param index="1">motor sequence number (a number from 1 to max number of motors on the vehicle)</param>
<param index="2">throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)</param>
<param index="3">throttle</param>
<param index="4">timeout (in seconds)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_GRIPPER" value="211">
<description>Mission command to operate EPM gripper</description>
<param index="1">gripper number (a number from 1 to max number of grippers on the vehicle)</param>
<param index="2">gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)</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_AUTOTUNE_ENABLE" value="212">
<description>Enable/disable autotune</description>
<param index="1">enable (1: enable, 0:disable)</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_NAV_ALTITUDE_WAIT" value="83">
<description>Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up.</description>
<param index="1">altitude (m)</param>
<param index="2">descent speed (m/s)</param>
<param index="3">Wiggle Time (s)</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>
<param index="2">Automatically retry on failure (0=no retry, 1=retry).</param>
<param index="3">Save without user input (0=require input, 1=autosave).</param>
<param index="4">Delay (seconds)</param>
<param index="5">Autoreboot (0=user reboot, 1=autoreboot)</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_ACCEPT_MAG_CAL" value="42425">
<description>Initiate a magnetometer calibration</description>
<param index="1">uint8_t bitmask of magnetometers (0 means all)</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_CANCEL_MAG_CAL" value="42426">
<description>Cancel a running magnetometer calibration</description>
<param index="1">uint8_t bitmask of magnetometers (0 means all)</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>
</enum>
<!-- AP_Limits Enums -->
<enum name="LIMITS_STATE">
<entry name="LIMITS_INIT" value="0"> <description> pre-initialization</description></entry>
<entry name="LIMITS_DISABLED" value="1"> <description> disabled</description></entry>
<entry name="LIMITS_ENABLED" value="2"> <description> checking limits</description></entry>
<entry name="LIMITS_TRIGGERED" value="3"> <description> a limit has been breached</description></entry>
<entry name="LIMITS_RECOVERING" value="4"> <description> taking action eg. RTL</description></entry>
<entry name="LIMITS_RECOVERED" value="5"> <description> we're no longer in breach of a limit</description></entry>
</enum>
<!-- AP_Limits Modules - power of 2 (1,2,4,8,16,32 etc) so we can send as bitfield -->
<enum name="LIMIT_MODULE">
<entry name="LIMIT_GPSLOCK" value="1"> <description> pre-initialization</description></entry>
<entry name="LIMIT_GEOFENCE" value="2"> <description> disabled</description></entry>
<entry name="LIMIT_ALTITUDE" value="4"> <description> checking limits</description></entry>
</enum>
<!-- RALLY flags - power of 2 (1,2,4,8,16,32,64,128) so we can send as a bitfield -->
<enum name="RALLY_FLAGS">
<description>Flags in RALLY_POINT message</description>
<entry name="FAVORABLE_WIND" value="1"> <description>Flag set when requiring favorable winds for landing. </description></entry>
<entry name="LAND_IMMEDIATELY" value="2"> <description>Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land.</description></entry>
</enum>
<!-- parachute action enum -->
<enum name="PARACHUTE_ACTION">
<entry name="PARACHUTE_DISABLE" value="0">
<description>Disable parachute release</description>
</entry>
<entry name="PARACHUTE_ENABLE" value="1">
<description>Enable parachute release</description>
</entry>
<entry name="PARACHUTE_RELEASE" value="2">
<description>Release parachute</description>
</entry>
</enum>
<!-- motor test type enum -->
<enum name="MOTOR_TEST_THROTTLE_TYPE">
<entry name="MOTOR_TEST_THROTTLE_PERCENT" value="0">
<description>throttle as a percentage from 0 ~ 100</description>
</entry>
<entry name="MOTOR_TEST_THROTTLE_PWM" value="1">
<description>throttle as an absolute PWM value (normally in range of 1000~2000)</description>
</entry>
<entry name="MOTOR_TEST_THROTTLE_PILOT" value="2">
<description>throttle pass-through from pilot's transmitter</description>
</entry>
</enum>
<!-- gripper action enum -->
<enum name="GRIPPER_ACTIONS">
<description>Gripper actions.</description>
<entry name="GRIPPER_ACTION_RELEASE" value="0">
<description>gripper release of cargo</description>
</entry>
<entry name="GRIPPER_ACTION_GRAB" value="1">
<description>gripper grabs onto cargo</description>
</entry>
</enum>
<!-- Camera event types -->
<enum name="CAMERA_STATUS_TYPES">
<entry name="CAMERA_STATUS_TYPE_HEARTBEAT" value="0"><description>Camera heartbeat, announce camera component ID at 1hz</description></entry>
<entry name="CAMERA_STATUS_TYPE_TRIGGER" value="1"><description>Camera image triggered</description></entry>
<entry name="CAMERA_STATUS_TYPE_DISCONNECT" value="2"><description>Camera connection lost</description></entry>
<entry name="CAMERA_STATUS_TYPE_ERROR" value="3"><description>Camera unknown error</description></entry>
<entry name="CAMERA_STATUS_TYPE_LOWBATT" value="4"><description>Camera battery low. Parameter p1 shows reported voltage</description></entry>
<entry name="CAMERA_STATUS_TYPE_LOWSTORE" value="5"><description>Camera storage low. Parameter p1 shows reported shots remaining</description></entry>
<entry name="CAMERA_STATUS_TYPE_LOWSTOREV" value="6"><description>Camera storage low. Parameter p1 shows reported video minutes remaining</description></entry>
</enum>
<!-- camera feedback flags, a little bit of future-proofing -->
<enum name="CAMERA_FEEDBACK_FLAGS">
<entry name="CAMERA_FEEDBACK_PHOTO" value="0"> <description>Shooting photos, not video</description></entry>
<entry name="CAMERA_FEEDBACK_VIDEO" value="1"> <description>Shooting video, not stills</description></entry>
<entry name="CAMERA_FEEDBACK_BADEXPOSURE" value="2"> <description>Unable to achieve requested exposure (e.g. shutter speed too low)</description></entry>
<entry name="CAMERA_FEEDBACK_CLOSEDLOOP" value="3"> <description>Closed loop feedback from camera, we know for sure it has successfully taken a picture</description></entry>
<entry name="CAMERA_FEEDBACK_OPENLOOP" value="4"> <description>Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture</description></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="FACTORY_TEST">
<entry name="FACTORY_TEST_AXIS_RANGE_LIMITS" value="0">
<description>Tests to make sure each axis can move to its mechanical limits</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_POWER_OFF" value="2">
<description>A HeroBus compatible GoPro is connected</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_CONNECTED_POWER_ON" value="3">
<description>A HeroBus compatible GoPro is connected</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_RECORDING" value="4">
<description>A HeroBus compatible GoPro is connected and recording</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_ERR_OVERTEMP" value="5">
<description>A HeroBus compatible GoPro is connected and overtemperature</description>
</entry>
<entry name="GOPRO_HEARTBEAT_STATUS_ERR_STORAGE" value="6">
<description>A HeroBus compatible GoPro is connected and storage is missing or full</description>
</entry>
</enum>
<enum name="GOPRO_SET_RESPONSE_RESULT">
<entry name="GOPRO_SET_RESPONSE_RESULT_FAILURE" value="0">
<description>The write message with ID indicated failed</description>
</entry>
<entry name="GOPRO_SET_RESPONSE_RESULT_SUCCESS" value="1">
<description>The write message with ID indicated succeeded</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_REQUEST_FAILED" value="254">
<description>(Get/___)</description>
</entry>
</enum>
<!-- led control pattern enums (enumeration of specific patterns) -->
<enum name="LED_CONTROL_PATTERN">
<entry name="LED_CONTROL_PATTERN_OFF" value="0"> <description>LED patterns off (return control to regular vehicle control)</description></entry>
<entry name="LED_CONTROL_PATTERN_FIRMWAREUPDATE" value="1"> <description>LEDs show pattern during firmware update</description></entry>
<entry name="LED_CONTROL_PATTERN_CUSTOM" value="255"> <description>Custom Pattern using custom bytes fields</description></entry>
</enum>
<!-- EKF_STATUS_FLAGS - these values should be bit-and with the messages flags field to know if flag has been set -->
<enum name="EKF_STATUS_FLAGS">
<description>Flags in EKF_STATUS message</description>
<entry name="EKF_ATTITUDE" value="1"> <description>set if EKF's attitude estimate is good</description></entry>
<entry name="EKF_VELOCITY_HORIZ" value="2"> <description>set if EKF's horizontal velocity estimate is good</description></entry>
<entry name="EKF_VELOCITY_VERT" value="4"> <description>set if EKF's vertical velocity estimate is good</description></entry>
<entry name="EKF_POS_HORIZ_REL" value="8"> <description>set if EKF's horizontal position (relative) estimate is good</description></entry>
<entry name="EKF_POS_HORIZ_ABS" value="16"> <description>set if EKF's horizontal position (absolute) estimate is good</description></entry>
<entry name="EKF_POS_VERT_ABS" value="32"> <description>set if EKF's vertical position (absolute) estimate is good</description></entry>
<entry name="EKF_POS_VERT_AGL" value="64"> <description>set if EKF's vertical position (above ground) estimate is good</description></entry>
<entry name="EKF_CONST_POS_MODE" value="128"> <description>EKF is in constant position mode and does not know it's absolute or relative position</description></entry>
<entry name="EKF_PRED_POS_HORIZ_REL" value="256"> <description>set if EKF's predicted horizontal position (relative) estimate is good</description></entry>
<entry name="EKF_PRED_POS_HORIZ_ABS" value="512"> <description>set if EKF's predicted horizontal position (absolute) estimate is good</description></entry>
</enum>
<enum name="PID_TUNING_AXIS">
<entry name="PID_TUNING_ROLL" value="1"></entry>
<entry name="PID_TUNING_PITCH" value="2"></entry>
<entry name="PID_TUNING_YAW" value="3"></entry>
<entry name="PID_TUNING_ACCZ" value="4"></entry>
<entry name="PID_TUNING_STEER" value="5"></entry>
</enum>
<enum name="MAG_CAL_STATUS">
<entry name="MAG_CAL_NOT_STARTED" value="0"></entry>
<entry name="MAG_CAL_WAITING_TO_START" value="1"></entry>
<entry name="MAG_CAL_RUNNING_STEP_ONE" value="2"></entry>
<entry name="MAG_CAL_RUNNING_STEP_TWO" value="3"></entry>
<entry name="MAG_CAL_SUCCESS" value="4"></entry>
<entry name="MAG_CAL_FAILED" value="5"></entry>
</enum>
</enums>
<messages>
<message id="150" name="SENSOR_OFFSETS">
<description>Offsets and calibrations values for hardware
sensors. This makes it easier to debug the calibration process.</description>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
<field type="float" name="mag_declination">magnetic declination (radians)</field>
<field type="int32_t" name="raw_press">raw pressure from barometer</field>
<field type="int32_t" name="raw_temp">raw temperature from barometer</field>
<field type="float" name="gyro_cal_x">gyro X calibration</field>
<field type="float" name="gyro_cal_y">gyro Y calibration</field>
<field type="float" name="gyro_cal_z">gyro Z calibration</field>
<field type="float" name="accel_cal_x">accel X calibration</field>
<field type="float" name="accel_cal_y">accel Y calibration</field>
<field type="float" name="accel_cal_z">accel Z calibration</field>
</message>
<message id="151" name="SET_MAG_OFFSETS">
<description>Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
</message>
<message id="152" name="MEMINFO">
<description>state of APM memory</description>
<field type="uint16_t" name="brkval">heap top</field>
<field type="uint16_t" name="freemem">free memory</field>
</message>
<message id="153" name="AP_ADC">
<description>raw ADC output</description>
<field type="uint16_t" name="adc1">ADC output 1</field>
<field type="uint16_t" name="adc2">ADC output 2</field>
<field type="uint16_t" name="adc3">ADC output 3</field>
<field type="uint16_t" name="adc4">ADC output 4</field>
<field type="uint16_t" name="adc5">ADC output 5</field>
<field type="uint16_t" name="adc6">ADC output 6</field>
</message>
<!-- Camera Controller Messages -->
<message name="DIGICAM_CONFIGURE" id="154">
<description>Configure on-board Camera Control System.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field>
<field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field>
<field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field>
<field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
<field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>
<message name="DIGICAM_CONTROL" id="155">
<description>Control on-board Camera Control System to take shots.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field>
<field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field>
<field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field>
<field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
<field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>
<!-- Camera Mount Messages -->
<message name="MOUNT_CONFIGURE" id="156">
<description>Message to configure a camera mount, directional antenna, etc.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="mount_mode" type="uint8_t" enum="MAV_MOUNT_MODE">mount operating mode (see MAV_MOUNT_MODE enum)</field>
<field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field>
<field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field>
<field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field>
</message>
<message name="MOUNT_CONTROL" id="157">
<description>Message to control a camera mount, directional antenna, etc.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
<field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
<field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
<field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field>
</message>
<message name="MOUNT_STATUS" id="158">
<description>Message with some status from APM to GCS about camera or antenna mount</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="pointing_a" type="int32_t">pitch(deg*100)</field>
<field name="pointing_b" type="int32_t">roll(deg*100)</field>
<field name="pointing_c" type="int32_t">yaw(deg*100)</field>
</message>
<!-- geo-fence messages -->
<message name="FENCE_POINT" id="160">
<description>A fence point. Used to set a point when from
GCS -> MAV. Also used to return a point from MAV -> GCS</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
<field name="count" type="uint8_t">total number of points (for sanity checking)</field>
<field name="lat" type="float">Latitude of point</field>
<field name="lng" type="float">Longitude of point</field>
</message>
<message name="FENCE_FETCH_POINT" id="161">
<description>Request a current fence point from MAV</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
</message>
<message name="FENCE_STATUS" id="162">
<description>Status of geo-fencing. Sent in extended
status stream when fencing enabled</description>
<field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field>
<field name="breach_count" type="uint16_t">number of fence breaches</field>
<field name="breach_type" type="uint8_t" enum="FENCE_BREACH">last breach type (see FENCE_BREACH_* enum)</field>
<field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field>
</message>
<message name="AHRS" id="163">
<description>Status of DCM attitude estimator</description>
<field type="float" name="omegaIx">X gyro drift estimate rad/s</field>
<field type="float" name="omegaIy">Y gyro drift estimate rad/s</field>
<field type="float" name="omegaIz">Z gyro drift estimate rad/s</field>
<field type="float" name="accel_weight">average accel_weight</field>
<field type="float" name="renorm_val">average renormalisation value</field>
<field type="float" name="error_rp">average error_roll_pitch value</field>
<field type="float" name="error_yaw">average error_yaw value</field>
</message>
<message name="SIMSTATE" id="164">
<description>Status of simulation environment, if used</description>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="xacc">X acceleration m/s/s</field>
<field type="float" name="yacc">Y acceleration m/s/s</field>
<field type="float" name="zacc">Z acceleration m/s/s</field>
<field type="float" name="xgyro">Angular speed around X axis rad/s</field>
<field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
<field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
<field type="int32_t" name="lat">Latitude in degrees * 1E7</field>
<field type="int32_t" name="lng">Longitude in degrees * 1E7</field>
</message>
<message name="HWSTATUS" id="165">
<description>Status of key hardware</description>
<field type="uint16_t" name="Vcc">board voltage (mV)</field>
<field type="uint8_t" name="I2Cerr">I2C error count</field>
</message>
<message name="RADIO" id="166">
<description>Status generated by radio</description>
<field type="uint8_t" name="rssi">local signal strength</field>
<field type="uint8_t" name="remrssi">remote signal strength</field>
<field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
<field type="uint8_t" name="noise">background noise level</field>
<field type="uint8_t" name="remnoise">remote background noise level</field>
<field type="uint16_t" name="rxerrors">receive errors</field>
<field type="uint16_t" name="fixed">count of error corrected packets</field>
</message>
<!-- AP_Limits status -->
<message name="LIMITS_STATUS" id="167">
<description>Status of AP_Limits. Sent in extended
status stream when AP_Limits is enabled</description>
<field name="limits_state" type="uint8_t" enum="LIMITS_STATE">state of AP_Limits, (see enum LimitState, LIMITS_STATE)</field>
<field name="last_trigger" type="uint32_t">time of last breach in milliseconds since boot</field>
<field name="last_action" type="uint32_t">time of last recovery action in milliseconds since boot</field>
<field name="last_recovery" type="uint32_t">time of last successful recovery in milliseconds since boot</field>
<field name="last_clear" type="uint32_t">time of last all-clear in milliseconds since boot</field>
<field name="breach_count" type="uint16_t">number of fence breaches</field>
<field name="mods_enabled" type="uint8_t">AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)</field>
<field name="mods_required" type="uint8_t">AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)</field>
<field name="mods_triggered" type="uint8_t">AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)</field>
</message>
<message name="WIND" id="168">
<description>Wind estimation</description>
<field type="float" name="direction">wind direction that wind is coming from (degrees)</field>
<field type="float" name="speed">wind speed in ground plane (m/s)</field>
<field type="float" name="speed_z">vertical wind speed (m/s)</field>
</message>
<message name="DATA16" id="169">
<description>Data packet, size 16</description>
<field type="uint8_t" name="type">data type</field>
<field type="uint8_t" name="len">data length</field>
<field type="uint8_t[16]" name="data">raw data</field>
</message>
<message name="DATA32" id="170">
<description>Data packet, size 32</description>
<field type="uint8_t" name="type">data type</field>
<field type="uint8_t" name="len">data length</field>
<field type="uint8_t[32]" name="data">raw data</field>
</message>
<message name="DATA64" id="171">
<description>Data packet, size 64</description>
<field type="uint8_t" name="type">data type</field>
<field type="uint8_t" name="len">data length</field>
<field type="uint8_t[64]" name="data">raw data</field>
</message>
<message name="DATA96" id="172">
<description>Data packet, size 96</description>
<field type="uint8_t" name="type">data type</field>
<field type="uint8_t" name="len">data length</field>
<field type="uint8_t[96]" name="data">raw data</field>
</message>
<message name="RANGEFINDER" id="173">
<description>Rangefinder reporting</description>
<field type="float" name="distance">distance in meters</field>
<field type="float" name="voltage">raw voltage if available, zero otherwise</field>
</message>
<message name="AIRSPEED_AUTOCAL" id="174">
<description>Airspeed auto-calibration</description>
<field type="float" name="vx">GPS velocity north m/s</field>
<field type="float" name="vy">GPS velocity east m/s</field>
<field type="float" name="vz">GPS velocity down m/s</field>
<field type="float" name="diff_pressure">Differential pressure pascals</field>
<field type="float" name="EAS2TAS">Estimated to true airspeed ratio</field>
<field type="float" name="ratio">Airspeed ratio</field>
<field type="float" name="state_x">EKF state x</field>
<field type="float" name="state_y">EKF state y</field>
<field type="float" name="state_z">EKF state z</field>
<field type="float" name="Pax">EKF Pax</field>
<field type="float" name="Pby">EKF Pby</field>
<field type="float" name="Pcz">EKF Pcz</field>
</message>
<!-- rally point messages -->
<message name="RALLY_POINT" id="175">
<description>A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 0)</field>
<field name="count" type="uint8_t">total number of points (for sanity checking)</field>
<field name="lat" type="int32_t">Latitude of point in degrees * 1E7</field>
<field name="lng" type="int32_t">Longitude of point in degrees * 1E7</field>
<field name="alt" type="int16_t">Transit / loiter altitude in meters relative to home</field>
<!-- Path planned landings are still in the future, but we want these fields ready: -->
<field name="break_alt" type="int16_t">Break altitude in meters relative to home</field>
<field name="land_dir" type="uint16_t">Heading to aim for when landing. In centi-degrees.</field>
<field name="flags" type="uint8_t">See RALLY_FLAGS enum for definition of the bitmask.</field>
</message>
<message name="RALLY_FETCH_POINT" id="176">
<description>Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 0)</field>
</message>
<message name="COMPASSMOT_STATUS" id="177">
<description>Status of compassmot calibration</description>
<field name="throttle" type="uint16_t">throttle (percent*10)</field>
<field name="current" type="float">current (amps)</field>
<field name="interference" type="uint16_t">interference (percent)</field>
<field name="CompensationX" type="float">Motor Compensation X</field>
<field name="CompensationY" type="float">Motor Compensation Y</field>
<field name="CompensationZ" type="float">Motor Compensation Z</field>
</message>
<!-- Coming soon
<message name="RALLY_LAND_POINT" id="177">
<description>A rally landing point. An aircraft loitering at a rally point may choose one of these points to land at.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 0)</field>
<field name="count" type="uint8_t">total number of points (for sanity checking)</field>
<field name="lat" type="int32_t">Latitude of point</field>
<field name="lng" type="int32_t">Longitude of point</field>
<field name="alt" type="uint16_t">Ground AGL (usually 0)</field>
</message>
<message name="RALLY_LAND_FETCH_POINT" id="178">
<description>Request a current rally land point from MAV</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 0)</field>
</message>
-->
<message name="AHRS2" id="178">
<description>Status of secondary AHRS filter if available</description>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="altitude">Altitude (MSL)</field>
<field type="int32_t" name="lat">Latitude in degrees * 1E7</field>
<field type="int32_t" name="lng">Longitude in degrees * 1E7</field>
</message>
<!-- camera event message from CCB to autopilot: for image trigger events but also things like heartbeat, error, low power, full card, etc -->
<message name="CAMERA_STATUS" id="179">
<description>Camera Event</description>
<field name="time_usec" type="uint64_t">Image timestamp (microseconds since UNIX epoch, according to camera clock)</field>
<field name="target_system" type="uint8_t" >System ID</field> <!-- support multiple concurrent vehicles -->
<field name="cam_idx" type="uint8_t" >Camera ID</field> <!-- component ID, to support multiple cameras -->
<field name="img_idx" type="uint16_t" >Image index</field> <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<field name="event_id" type="uint8_t" >See CAMERA_STATUS_TYPES enum for definition of the bitmask</field>
<field name="p1" type="float" >Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
<field name="p2" type="float" >Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
<field name="p3" type="float" >Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
<field name="p4" type="float" >Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum)</field>
</message>
<!-- camera feedback message - can be originated from CCB (in response to a CAMERA_STATUS), or directly from the autopilot as part of a DO_DIGICAM_CONTROL-->
<message name="CAMERA_FEEDBACK" id="180">
<description>Camera Capture Feedback</description>
<field name="time_usec" type="uint64_t">Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB)</field>
<field name="target_system" type="uint8_t" >System ID</field> <!-- support multiple concurrent vehicles -->
<field name="cam_idx" type="uint8_t" >Camera ID</field> <!-- component ID, to support multiple cameras -->
<field name="img_idx" type="uint16_t">Image index</field> <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
<field name="lat" type="int32_t" >Latitude in (deg * 1E7)</field>
<field name="lng" type="int32_t" >Longitude in (deg * 1E7)</field>
<field name="alt_msl" type="float" >Altitude Absolute (meters AMSL)</field>
<field name="alt_rel" type="float" >Altitude Relative (meters above HOME location)</field>
<field name="roll" type="float" >Camera Roll angle (earth frame, degrees, +-180)</field> <!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
<field name="pitch" type="float" >Camera Pitch angle (earth frame, degrees, +-180)</field> <!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
<field name="yaw" type="float" >Camera Yaw (earth frame, degrees, 0-360, true)</field> <!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
<field name="foc_len" type="float" >Focal Length (mm)</field> <!-- per-image to support zooms. Zero means fixed focal length or unknown. Should be true mm, not scaled to 35mm film equivalent -->
<field name="flags" type="uint8_t" >See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask</field> <!-- future proofing -->
</message>
<message name="BATTERY2" id="181">
<description>2nd Battery status</description>
<field type="uint16_t" name="voltage">voltage in millivolts</field>
<field type="int16_t" name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field>
</message>
<message name="AHRS3" id="182">
<description>Status of third AHRS filter if available. This is for ANU research group (Ali and Sean)</description>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="altitude">Altitude (MSL)</field>
<field type="int32_t" name="lat">Latitude in degrees * 1E7</field>
<field type="int32_t" name="lng">Longitude in degrees * 1E7</field>
<field type="float" name="v1">test variable1</field>
<field type="float" name="v2">test variable2</field>
<field type="float" name="v3">test variable3</field>
<field type="float" name="v4">test variable4</field>
</message>
<message name="AUTOPILOT_VERSION_REQUEST" id="183">
<description>Request the autopilot version from the system/component.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message name="LED_CONTROL" id="186">
<description>Control vehicle LEDs</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="instance">Instance (LED instance to control or 255 for all LEDs)</field>
<field type="uint8_t" name="pattern">Pattern (see LED_PATTERN_ENUM)</field>
<field type="uint8_t" name="custom_len">Custom Byte Length</field>
<field type="uint8_t[24]" name="custom_bytes">Custom Bytes</field>
</message>
<message name="MAG_CAL_PROGRESS" id="191">
<description>Reports progress of compass calibration.</description>
<field type="uint8_t" name="compass_id">Compass being calibrated</field>
<field type="uint8_t" name="cal_mask">Bitmask of compasses being calibrated</field>
<field type="uint8_t" name="cal_status">Status (see MAG_CAL_STATUS enum)</field>
<field type="uint8_t" name="attempt">Attempt number</field>
<field type="uint8_t" name="completion_pct">Completion percentage</field>
<field type="uint8_t[10]" name="completion_mask">Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid)</field>
<field type="float" name="direction_x">Body frame direction vector for display</field>
<field type="float" name="direction_y">Body frame direction vector for display</field>
<field type="float" name="direction_z">Body frame direction vector for display</field>
</message>
<message name="MAG_CAL_REPORT" id="192">
<description>Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.</description>
<field type="uint8_t" name="compass_id">Compass being calibrated</field>
<field type="uint8_t" name="cal_mask">Bitmask of compasses being calibrated</field>
<field type="uint8_t" name="cal_status">Status (see MAG_CAL_STATUS enum)</field>
<field type="uint8_t" name="autosaved">0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters</field>
<field type="float" name="fitness">RMS milligauss residuals</field>
<field type="float" name="ofs_x">X offset</field>
<field type="float" name="ofs_y">Y offset</field>
<field type="float" name="ofs_z">Z offset</field>
<field type="float" name="diag_x">X diagonal (matrix 11)</field>
<field type="float" name="diag_y">Y diagonal (matrix 22)</field>
<field type="float" name="diag_z">Z diagonal (matrix 33)</field>
<field type="float" name="offdiag_x">X off-diagonal (matrix 12 and 21)</field>
<field type="float" name="offdiag_y">Y off-diagonal (matrix 13 and 31)</field>
<field type="float" name="offdiag_z">Z off-diagonal (matrix 32 and 23)</field>
</message>
<!-- EKF status message from autopilot to GCS. -->
<message name="EKF_STATUS_REPORT" id="193">
<description>EKF Status message including flags and variances</description>
<field name="flags" type="uint16_t">Flags</field> <!-- supported flags see EKF_STATUS_FLAGS enum -->
<field name="velocity_variance" type="float">Velocity variance</field> <!-- below 0.5 is good, 0.5~0.79 is warning, 0.8 or higher is bad -->
<field name="pos_horiz_variance" type="float">Horizontal Position variance</field>
<field name="pos_vert_variance" type="float">Vertical Position variance</field>
<field name="compass_variance" type="float">Compass variance</field>
<field name="terrain_alt_variance" type="float">Terrain Altitude variance</field>
</message>
<!-- realtime PID tuning message -->
<message name="PID_TUNING" id="194">
<description>PID tuning information</description>
<field name="axis" type="uint8_t" enum="PID_TUNING_AXIS">axis</field>
<field name="desired" type="float">desired rate (degrees/s)</field>
<field name="achieved" type="float">achieved rate (degrees/s)</field>
<field name="FF" type="float">FF component</field>
<field name="P" type="float">P component</field>
<field name="I" type="float">I component</field>
<field name="D" type="float">D component</field>
</message>
<message name="GIMBAL_REPORT" id="200">
<description>3 axis gimbal mesuraments</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="delta_time">Time since last update (seconds)</field>
<field type="float" name="delta_angle_x">Delta angle X (radians)</field>
<field type="float" name="delta_angle_y">Delta angle Y (radians)</field>
<field type="float" name="delta_angle_z">Delta angle X (radians)</field>
<field type="float" name="delta_velocity_x">Delta velocity X (m/s)</field>
<field type="float" name="delta_velocity_y">Delta velocity Y (m/s)</field>
<field type="float" name="delta_velocity_z">Delta velocity Z (m/s)</field>
<field type="float" name="joint_roll"> Joint ROLL (radians)</field>
<field type="float" name="joint_el"> Joint EL (radians)</field>
<field type="float" name="joint_az"> Joint AZ (radians)</field>
</message>
<message name="GIMBAL_CONTROL" id="201">
<description>Control message for rate gimbal</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="demanded_rate_x">Demanded angular rate X (rad/s)</field>
<field type="float" name="demanded_rate_y">Demanded angular rate Y (rad/s)</field>
<field type="float" name="demanded_rate_z">Demanded angular rate Z (rad/s)</field>
</message>
<message name="GIMBAL_RESET" id="202">
<description>
Causes the gimbal to reset and boot as if it was just powered on
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="GIMBAL_AXIS_CALIBRATION_PROGRESS" id="203">
<description>
Reports progress and success or failure of gimbal axis calibration procedure
</description>
<field name="calibration_axis" type="uint8_t" enum="GIMBAL_AXIS">Which gimbal axis we're reporting calibration progress for</field>
<field name="calibration_progress" type="uint8_t">The current calibration progress for this axis, 0x64=100%</field>
<field name="calibration_status" type="uint8_t" enum="GIMBAL_AXIS_CALIBRATION_STATUS">The status of the running calibration</field>
</message>
<message name="GIMBAL_SET_HOME_OFFSETS" id="204">
<description>
Instructs the gimbal to set its current position as its new home position. Will primarily be used for factory calibration
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="GIMBAL_HOME_OFFSET_CALIBRATION_RESULT" id="205">
<description>
Sent by the gimbal after it receives a SET_HOME_OFFSETS message to indicate the result of the home offset calibration
</description>
<field name="calibration_result" type="uint8_t" enum="GIMBAL_AXIS_CALIBRATION_STATUS">The result of the home offset calibration</field>
</message>
<message name="GIMBAL_SET_FACTORY_PARAMETERS" id="206">
<description>
Set factory configuration parameters (such as assembly date and time, and serial number). This is only intended to be used
during manufacture, not by end users, so it is protected by a simple checksum of sorts (this won't stop anybody determined,
it's mostly just to keep the average user from trying to modify these values. This will need to be revisited if that isn't
adequate.
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="magic_1" type="uint32_t">Magic number 1 for validation</field>
<field name="magic_2" type="uint32_t">Magic number 2 for validation</field>
<field name="magic_3" type="uint32_t">Magic number 3 for validation</field>
<field name="assembly_year" type="uint16_t">Assembly Date Year</field>
<field name="assembly_month" type="uint8_t">Assembly Date Month</field>
<field name="assembly_day" type="uint8_t">Assembly Date Day</field>
<field name="assembly_hour" type="uint8_t">Assembly Time Hour</field>
<field name="assembly_minute" type="uint8_t">Assembly Time Minute</field>
<field name="assembly_second" type="uint8_t">Assembly Time Second</field>
<field name="serial_number_pt_1" type="uint32_t">Unit Serial Number Part 1 (part code, design, language/country)</field>
<field name="serial_number_pt_2" type="uint32_t">Unit Serial Number Part 2 (option, year, month)</field>
<field name="serial_number_pt_3" type="uint32_t">Unit Serial Number Part 3 (incrementing serial number per month)</field>
</message>
<message name="GIMBAL_FACTORY_PARAMETERS_LOADED" id="207">
<description>
Sent by the gimbal after the factory parameters are successfully loaded, to inform the factory software that the load is complete
</description>
<field name="dummy" type="uint8_t">Dummy field because mavgen doesn't allow messages with no fields</field>
</message>
<message name="GIMBAL_ERASE_FIRMWARE_AND_CONFIG" id="208">
<description>
Commands the gimbal to erase its firmware image and flash configuration, leaving only the bootloader. The gimbal will then reboot into the bootloader,
ready for the load of a new application firmware image. Erasing the flash configuration will cause the gimbal to re-perform axis calibration when a
new firmware image is loaded, and will cause all tuning parameters to return to their factory defaults. WARNING: sending this command will render a
gimbal inoperable until a new firmware image is loaded onto it. For this reason, a particular "knock" value must be sent for the command to take effect.
Use this command at your own risk
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="knock" type="uint32_t">Knock value to confirm this is a valid request</field>
</message>
<message name="GIMBAL_PERFORM_FACTORY_TESTS" id="209">
<description>
Command the gimbal to perform a series of factory tests. Should not be needed by end users
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="GIMBAL_REPORT_FACTORY_TESTS_PROGRESS" id="210">
<description>
Reports the current status of a section of a running factory test
</description>
<field name="test" type="uint8_t" enum="FACTORY_TEST">Which factory test is currently running</field>
<field name="test_section" type="uint8_t">Which section of the test is currently running. The meaning of this is test-dependent</field>
<field name="test_section_progress" type="uint8_t">The progress of the current test section, 0x64=100%</field>
<field name="test_status" type="uint8_t">The status of the currently executing test section. The meaning of this is test and section-dependent</field>
</message>
<message name="GIMBAL_REQUEST_AXIS_CALIBRATION_STATUS" id="211">
<description>
Requests the calibration status for all gimbal axes. Should result in a GIMBAL_REPORT_AXIS_CALIBRATION_STATUS message being generated by the gimbal
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="GIMBAL_REPORT_AXIS_CALIBRATION_STATUS" id="212">
<description>
Reports the calibration status for each gimbal axis (whether the axis requires calibration or not)
</description>
<field name="yaw_requires_calibration" type="uint8_t" enum="GIMBAL_AXIS_CALIBRATION_REQUIRED">Whether or not the yaw axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration</field>
<field name="pitch_requires_calibration" type="uint8_t" enum="GIMBAL_AXIS_CALIBRATION_REQUIRED">Whether or not the pitch axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration</field>
<field name="roll_requires_calibration" type="uint8_t" enum="GIMBAL_AXIS_CALIBRATION_REQUIRED">Whether or not the roll axis requires calibration, see GIMBAL_AXIS_CALIBRATION_REQUIRED enumeration</field>
</message>
<message name="GIMBAL_REQUEST_AXIS_CALIBRATION" id="213">
<description>
Requests any currently uncalibrated gimbal axes to run the axis calibration procedure. An axis is considered uncalibrated if its commutation calibration
slope and intercept are 0
</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<!-- 214 RESERVED for more GIMBAL -->
<!-- GoPro Messages -->
<message name="GOPRO_HEARTBEAT" id="215">
<description>Heartbeat from a HeroBus attached GoPro</description>
<field name="status" type="uint8_t" enum="GOPRO_HEARTBEAT_STATUS">Status</field>
</message>
<message name="GOPRO_GET_REQUEST" id="216">
<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 name="cmd_id" type="uint8_t" enum="GOPRO_COMMAND">Command ID</field>
</message>
<message name="GOPRO_GET_RESPONSE" id="217">
<description>Response from a GOPRO_COMMAND get request</description>
<field name="cmd_id" type="uint8_t" enum="GOPRO_COMMAND">Command ID</field>
<field name="value" type="uint8_t">Value</field>
</message>
<message name="GOPRO_SET_REQUEST" id="218">
<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 name="cmd_id" type="uint8_t" enum="GOPRO_COMMAND">Command ID</field>
<field name="value" type="uint8_t">Value</field>
</message>
<message name="GOPRO_SET_RESPONSE" id="219">
<description>Response from a GOPRO_COMMAND set request</description>
<field name="cmd_id" type="uint8_t" enum="GOPRO_COMMAND">Command ID</field>
<field name="result" type="uint8_t" enum="GOPRO_SET_RESPONSE_RESULT">Result</field>
</message>
<!-- 219 to 225 RESERVED for more GOPRO-->
<message name="RPM" id="226">
<description>RPM sensor output</description>
<field name="rpm1" type="float">RPM Sensor1</field>
<field name="rpm2" type="float">RPM Sensor2</field>
</message>
</messages>
</mavlink>