mirror of
https://github.com/OpenSolo/OpenSolo.git
synced 2025-04-29 22:24:32 +02:00
709 lines
55 KiB
C
709 lines
55 KiB
C
/** @file
|
|
* @brief MAVLink comm protocol generated from ardupilotmega.xml
|
|
* @see http://mavlink.org
|
|
*/
|
|
#ifndef MAVLINK_ARDUPILOTMEGA_H
|
|
#define MAVLINK_ARDUPILOTMEGA_H
|
|
|
|
#ifndef MAVLINK_H
|
|
#error Wrong include order: MAVLINK_ARDUPILOTMEGA.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
|
|
#endif
|
|
|
|
#ifdef __cplusplus
|
|
extern "C" {
|
|
#endif
|
|
|
|
// MESSAGE LENGTHS AND CRCS
|
|
|
|
#ifndef MAVLINK_MESSAGE_LENGTHS
|
|
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 229, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 0, 0, 0, 0, 0, 0, 36, 60, 14, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 40, 2, 206, 7, 29, 0, 0, 0, 0, 27, 44, 22, 25, 0, 0, 0, 0, 0, 42, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 3, 3, 6, 7, 2, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
|
|
#endif
|
|
|
|
#ifndef MAVLINK_MESSAGE_CRCS
|
|
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 0, 0, 0, 0, 0, 0, 154, 178, 255, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 229, 85, 159, 186, 72, 0, 0, 0, 0, 92, 36, 71, 98, 0, 0, 0, 0, 0, 134, 205, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 69, 101, 50, 202, 17, 162, 0, 0, 0, 0, 0, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
|
|
#endif
|
|
|
|
#ifndef MAVLINK_MESSAGE_INFO
|
|
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, MAVLINK_MESSAGE_INFO_BATTERY2, MAVLINK_MESSAGE_INFO_AHRS3, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST, MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK, MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS, MAVLINK_MESSAGE_INFO_LED_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT, MAVLINK_MESSAGE_INFO_PID_TUNING, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT, MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT, MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT, MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE, MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_ACCURACY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
|
|
#endif
|
|
|
|
#include "../protocol.h"
|
|
|
|
#define MAVLINK_ENABLED_ARDUPILOTMEGA
|
|
|
|
// ENUM DEFINITIONS
|
|
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_MAV_CMD
|
|
#define HAVE_ENUM_MAV_CMD
|
|
typedef enum MAV_CMD
|
|
{
|
|
MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */
|
|
MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
|
MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
|
|
MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
|
|
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
|
|
MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
|
|
MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
|
|
MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */
|
|
MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
|
MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
|
|
MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
|
|
MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
|
|
MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_GRIPPER=211, /* Mission command to operate EPM gripper |gripper number (a number from 1 to max number of grippers on the vehicle)| gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
|
|
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
|
|
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */
|
|
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
|
|
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
|
|
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
|
|
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
|
|
MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
|
|
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */
|
|
MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */
|
|
MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */
|
|
MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */
|
|
MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */
|
|
MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */
|
|
MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */
|
|
MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */
|
|
MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
|
|
MAV_CMD_POWER_OFF_INITIATED=42000, /* A system wide power-off event has been initiated. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_SOLO_BTN_FLY_CLICK=42001, /* FLY button has been clicked. |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_SOLO_BTN_FLY_HOLD=42002, /* FLY button has been held for 1.5 seconds. |Takeoff altitude| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_SOLO_BTN_PAUSE_CLICK=42003, /* PAUSE button has been clicked. |1 if Solo is in a shot mode, 0 otherwise| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay (seconds)| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_SET_FACTORY_TEST_MODE=42427, /* Command autopilot to get into factory test/diagnostic mode |0 means get out of test mode, 1 means get into test mode| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_DO_SEND_BANNER=42428, /* Reply with the version banner |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_GIMBAL_RESET=42501, /* Causes the gimbal to reset and boot as if it was just powered on |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS=42502, /* Reports progress and success or failure of gimbal axis calibration procedure |Gimbal axis we're reporting calibration progress for| Current calibration progress for this axis, 0x64=100%| Status of the calibration| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION=42503, /* Starts commutation calibration on the gimbal |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
|
MAV_CMD_GIMBAL_FULL_RESET=42505, /* Erases gimbal application and parameters |Magic number| Magic number| Magic number| Magic number| Magic number| Magic number| Magic number| */
|
|
MAV_CMD_ENUM_END=42506, /* | */
|
|
} MAV_CMD;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_LIMITS_STATE
|
|
#define HAVE_ENUM_LIMITS_STATE
|
|
typedef enum LIMITS_STATE
|
|
{
|
|
LIMITS_INIT=0, /* pre-initialization | */
|
|
LIMITS_DISABLED=1, /* disabled | */
|
|
LIMITS_ENABLED=2, /* checking limits | */
|
|
LIMITS_TRIGGERED=3, /* a limit has been breached | */
|
|
LIMITS_RECOVERING=4, /* taking action eg. RTL | */
|
|
LIMITS_RECOVERED=5, /* we're no longer in breach of a limit | */
|
|
LIMITS_STATE_ENUM_END=6, /* | */
|
|
} LIMITS_STATE;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_LIMIT_MODULE
|
|
#define HAVE_ENUM_LIMIT_MODULE
|
|
typedef enum LIMIT_MODULE
|
|
{
|
|
LIMIT_GPSLOCK=1, /* pre-initialization | */
|
|
LIMIT_GEOFENCE=2, /* disabled | */
|
|
LIMIT_ALTITUDE=4, /* checking limits | */
|
|
LIMIT_MODULE_ENUM_END=5, /* | */
|
|
} LIMIT_MODULE;
|
|
#endif
|
|
|
|
/** @brief Flags in RALLY_POINT message */
|
|
#ifndef HAVE_ENUM_RALLY_FLAGS
|
|
#define HAVE_ENUM_RALLY_FLAGS
|
|
typedef enum RALLY_FLAGS
|
|
{
|
|
FAVORABLE_WIND=1, /* Flag set when requiring favorable winds for landing. | */
|
|
LAND_IMMEDIATELY=2, /* 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. | */
|
|
RALLY_FLAGS_ENUM_END=3, /* | */
|
|
} RALLY_FLAGS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_PARACHUTE_ACTION
|
|
#define HAVE_ENUM_PARACHUTE_ACTION
|
|
typedef enum PARACHUTE_ACTION
|
|
{
|
|
PARACHUTE_DISABLE=0, /* Disable parachute release | */
|
|
PARACHUTE_ENABLE=1, /* Enable parachute release | */
|
|
PARACHUTE_RELEASE=2, /* Release parachute | */
|
|
PARACHUTE_ACTION_ENUM_END=3, /* | */
|
|
} PARACHUTE_ACTION;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE
|
|
#define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE
|
|
typedef enum MOTOR_TEST_THROTTLE_TYPE
|
|
{
|
|
MOTOR_TEST_THROTTLE_PERCENT=0, /* throttle as a percentage from 0 ~ 100 | */
|
|
MOTOR_TEST_THROTTLE_PWM=1, /* throttle as an absolute PWM value (normally in range of 1000~2000) | */
|
|
MOTOR_TEST_THROTTLE_PILOT=2, /* throttle pass-through from pilot's transmitter | */
|
|
MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */
|
|
} MOTOR_TEST_THROTTLE_TYPE;
|
|
#endif
|
|
|
|
/** @brief Gripper actions. */
|
|
#ifndef HAVE_ENUM_GRIPPER_ACTIONS
|
|
#define HAVE_ENUM_GRIPPER_ACTIONS
|
|
typedef enum GRIPPER_ACTIONS
|
|
{
|
|
GRIPPER_ACTION_RELEASE=0, /* gripper release of cargo | */
|
|
GRIPPER_ACTION_GRAB=1, /* gripper grabs onto cargo | */
|
|
GRIPPER_ACTIONS_ENUM_END=2, /* | */
|
|
} GRIPPER_ACTIONS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_CAMERA_STATUS_TYPES
|
|
#define HAVE_ENUM_CAMERA_STATUS_TYPES
|
|
typedef enum CAMERA_STATUS_TYPES
|
|
{
|
|
CAMERA_STATUS_TYPE_HEARTBEAT=0, /* Camera heartbeat, announce camera component ID at 1hz | */
|
|
CAMERA_STATUS_TYPE_TRIGGER=1, /* Camera image triggered | */
|
|
CAMERA_STATUS_TYPE_DISCONNECT=2, /* Camera connection lost | */
|
|
CAMERA_STATUS_TYPE_ERROR=3, /* Camera unknown error | */
|
|
CAMERA_STATUS_TYPE_LOWBATT=4, /* Camera battery low. Parameter p1 shows reported voltage | */
|
|
CAMERA_STATUS_TYPE_LOWSTORE=5, /* Camera storage low. Parameter p1 shows reported shots remaining | */
|
|
CAMERA_STATUS_TYPE_LOWSTOREV=6, /* Camera storage low. Parameter p1 shows reported video minutes remaining | */
|
|
CAMERA_STATUS_TYPES_ENUM_END=7, /* | */
|
|
} CAMERA_STATUS_TYPES;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_CAMERA_FEEDBACK_FLAGS
|
|
#define HAVE_ENUM_CAMERA_FEEDBACK_FLAGS
|
|
typedef enum CAMERA_FEEDBACK_FLAGS
|
|
{
|
|
VIDEO=1, /* Shooting video, not stills | */
|
|
BADEXPOSURE=2, /* Unable to achieve requested exposure (e.g. shutter speed too low) | */
|
|
CLOSEDLOOP=3, /* Closed loop feedback from camera, we know for sure it has successfully taken a picture | */
|
|
OPENLOOP=4, /* Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture | */
|
|
CAMERA_FEEDBACK_FLAGS_ENUM_END=5, /* | */
|
|
} CAMERA_FEEDBACK_FLAGS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_MAV_MODE_GIMBAL
|
|
#define HAVE_ENUM_MAV_MODE_GIMBAL
|
|
typedef enum MAV_MODE_GIMBAL
|
|
{
|
|
MAV_MODE_GIMBAL_UNINITIALIZED=0, /* Gimbal is powered on but has not started initializing yet | */
|
|
MAV_MODE_GIMBAL_CALIBRATING_PITCH=1, /* Gimbal is currently running calibration on the pitch axis | */
|
|
MAV_MODE_GIMBAL_CALIBRATING_ROLL=2, /* Gimbal is currently running calibration on the roll axis | */
|
|
MAV_MODE_GIMBAL_CALIBRATING_YAW=3, /* Gimbal is currently running calibration on the yaw axis | */
|
|
MAV_MODE_GIMBAL_INITIALIZED=4, /* Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter | */
|
|
MAV_MODE_GIMBAL_ACTIVE=5, /* Gimbal is actively stabilizing | */
|
|
MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT=6, /* 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 | */
|
|
MAV_MODE_GIMBAL_ENUM_END=7, /* | */
|
|
} MAV_MODE_GIMBAL;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GIMBAL_AXIS
|
|
#define HAVE_ENUM_GIMBAL_AXIS
|
|
typedef enum GIMBAL_AXIS
|
|
{
|
|
GIMBAL_AXIS_YAW=0, /* Gimbal yaw axis | */
|
|
GIMBAL_AXIS_PITCH=1, /* Gimbal pitch axis | */
|
|
GIMBAL_AXIS_ROLL=2, /* Gimbal roll axis | */
|
|
GIMBAL_AXIS_ENUM_END=3, /* | */
|
|
} GIMBAL_AXIS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_STATUS
|
|
#define HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_STATUS
|
|
typedef enum GIMBAL_AXIS_CALIBRATION_STATUS
|
|
{
|
|
GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS=0, /* Axis calibration is in progress | */
|
|
GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED=1, /* Axis calibration succeeded | */
|
|
GIMBAL_AXIS_CALIBRATION_STATUS_FAILED=2, /* Axis calibration failed | */
|
|
GIMBAL_AXIS_CALIBRATION_STATUS_ENUM_END=3, /* | */
|
|
} GIMBAL_AXIS_CALIBRATION_STATUS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_REQUIRED
|
|
#define HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_REQUIRED
|
|
typedef enum GIMBAL_AXIS_CALIBRATION_REQUIRED
|
|
{
|
|
GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN=0, /* Whether or not this axis requires calibration is unknown at this time | */
|
|
GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE=1, /* This axis requires calibration | */
|
|
GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE=2, /* This axis does not require calibration | */
|
|
GIMBAL_AXIS_CALIBRATION_REQUIRED_ENUM_END=3, /* | */
|
|
} GIMBAL_AXIS_CALIBRATION_REQUIRED;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_HEARTBEAT_STATUS
|
|
#define HAVE_ENUM_GOPRO_HEARTBEAT_STATUS
|
|
typedef enum GOPRO_HEARTBEAT_STATUS
|
|
{
|
|
GOPRO_HEARTBEAT_STATUS_DISCONNECTED=0, /* No GoPro connected | */
|
|
GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE=1, /* The detected GoPro is not HeroBus compatible | */
|
|
GOPRO_HEARTBEAT_STATUS_CONNECTED=2, /* A HeroBus compatible GoPro is connected | */
|
|
GOPRO_HEARTBEAT_STATUS_ERROR=3, /* An unrecoverable error was encountered with the connected GoPro, it may require a power cycle | */
|
|
GOPRO_HEARTBEAT_STATUS_ENUM_END=4, /* | */
|
|
} GOPRO_HEARTBEAT_STATUS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_HEARTBEAT_FLAGS
|
|
#define HAVE_ENUM_GOPRO_HEARTBEAT_FLAGS
|
|
typedef enum GOPRO_HEARTBEAT_FLAGS
|
|
{
|
|
GOPRO_FLAG_RECORDING=1, /* GoPro is currently recording | */
|
|
GOPRO_HEARTBEAT_FLAGS_ENUM_END=2, /* | */
|
|
} GOPRO_HEARTBEAT_FLAGS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_REQUEST_STATUS
|
|
#define HAVE_ENUM_GOPRO_REQUEST_STATUS
|
|
typedef enum GOPRO_REQUEST_STATUS
|
|
{
|
|
GOPRO_REQUEST_SUCCESS=0, /* The write message with ID indicated succeeded | */
|
|
GOPRO_REQUEST_FAILED=1, /* The write message with ID indicated failed | */
|
|
GOPRO_REQUEST_STATUS_ENUM_END=2, /* | */
|
|
} GOPRO_REQUEST_STATUS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_COMMAND
|
|
#define HAVE_ENUM_GOPRO_COMMAND
|
|
typedef enum GOPRO_COMMAND
|
|
{
|
|
GOPRO_COMMAND_POWER=0, /* (Get/Set) | */
|
|
GOPRO_COMMAND_CAPTURE_MODE=1, /* (Get/Set) | */
|
|
GOPRO_COMMAND_SHUTTER=2, /* (___/Set) | */
|
|
GOPRO_COMMAND_BATTERY=3, /* (Get/___) | */
|
|
GOPRO_COMMAND_MODEL=4, /* (Get/___) | */
|
|
GOPRO_COMMAND_VIDEO_SETTINGS=5, /* (Get/Set) | */
|
|
GOPRO_COMMAND_LOW_LIGHT=6, /* (Get/Set) | */
|
|
GOPRO_COMMAND_PHOTO_RESOLUTION=7, /* (Get/Set) | */
|
|
GOPRO_COMMAND_PHOTO_BURST_RATE=8, /* (Get/Set) | */
|
|
GOPRO_COMMAND_PROTUNE=9, /* (Get/Set) | */
|
|
GOPRO_COMMAND_PROTUNE_WHITE_BALANCE=10, /* (Get/Set) Hero 3+ Only | */
|
|
GOPRO_COMMAND_PROTUNE_COLOUR=11, /* (Get/Set) Hero 3+ Only | */
|
|
GOPRO_COMMAND_PROTUNE_GAIN=12, /* (Get/Set) Hero 3+ Only | */
|
|
GOPRO_COMMAND_PROTUNE_SHARPNESS=13, /* (Get/Set) Hero 3+ Only | */
|
|
GOPRO_COMMAND_PROTUNE_EXPOSURE=14, /* (Get/Set) Hero 3+ Only | */
|
|
GOPRO_COMMAND_TIME=15, /* (Get/Set) | */
|
|
GOPRO_COMMAND_CHARGING=16, /* (Get/Set) | */
|
|
GOPRO_COMMAND_ENUM_END=17, /* | */
|
|
} GOPRO_COMMAND;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_CAPTURE_MODE
|
|
#define HAVE_ENUM_GOPRO_CAPTURE_MODE
|
|
typedef enum GOPRO_CAPTURE_MODE
|
|
{
|
|
GOPRO_CAPTURE_MODE_VIDEO=0, /* Video mode | */
|
|
GOPRO_CAPTURE_MODE_PHOTO=1, /* Photo mode | */
|
|
GOPRO_CAPTURE_MODE_BURST=2, /* Burst mode, hero 3+ only | */
|
|
GOPRO_CAPTURE_MODE_TIME_LAPSE=3, /* Time lapse mode, hero 3+ only | */
|
|
GOPRO_CAPTURE_MODE_MULTI_SHOT=4, /* Multi shot mode, hero 4 only | */
|
|
GOPRO_CAPTURE_MODE_PLAYBACK=5, /* Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black | */
|
|
GOPRO_CAPTURE_MODE_SETUP=6, /* Playback mode, hero 4 only | */
|
|
GOPRO_CAPTURE_MODE_UNKNOWN=255, /* Mode not yet known | */
|
|
GOPRO_CAPTURE_MODE_ENUM_END=256, /* | */
|
|
} GOPRO_CAPTURE_MODE;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_RESOLUTION
|
|
#define HAVE_ENUM_GOPRO_RESOLUTION
|
|
typedef enum GOPRO_RESOLUTION
|
|
{
|
|
GOPRO_RESOLUTION_480p=0, /* 848 x 480 (480p) | */
|
|
GOPRO_RESOLUTION_720p=1, /* 1280 x 720 (720p) | */
|
|
GOPRO_RESOLUTION_960p=2, /* 1280 x 960 (960p) | */
|
|
GOPRO_RESOLUTION_1080p=3, /* 1920 x 1080 (1080p) | */
|
|
GOPRO_RESOLUTION_1440p=4, /* 1920 x 1440 (1440p) | */
|
|
GOPRO_RESOLUTION_2_7k_17_9=5, /* 2704 x 1440 (2.7k-17:9) | */
|
|
GOPRO_RESOLUTION_2_7k_16_9=6, /* 2704 x 1524 (2.7k-16:9) | */
|
|
GOPRO_RESOLUTION_2_7k_4_3=7, /* 2704 x 2028 (2.7k-4:3) | */
|
|
GOPRO_RESOLUTION_4k_16_9=8, /* 3840 x 2160 (4k-16:9) | */
|
|
GOPRO_RESOLUTION_4k_17_9=9, /* 4096 x 2160 (4k-17:9) | */
|
|
GOPRO_RESOLUTION_720p_SUPERVIEW=10, /* 1280 x 720 (720p-SuperView) | */
|
|
GOPRO_RESOLUTION_1080p_SUPERVIEW=11, /* 1920 x 1080 (1080p-SuperView) | */
|
|
GOPRO_RESOLUTION_2_7k_SUPERVIEW=12, /* 2704 x 1520 (2.7k-SuperView) | */
|
|
GOPRO_RESOLUTION_4k_SUPERVIEW=13, /* 3840 x 2160 (4k-SuperView) | */
|
|
GOPRO_RESOLUTION_ENUM_END=14, /* | */
|
|
} GOPRO_RESOLUTION;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_FRAME_RATE
|
|
#define HAVE_ENUM_GOPRO_FRAME_RATE
|
|
typedef enum GOPRO_FRAME_RATE
|
|
{
|
|
GOPRO_FRAME_RATE_12=0, /* 12 FPS | */
|
|
GOPRO_FRAME_RATE_15=1, /* 15 FPS | */
|
|
GOPRO_FRAME_RATE_24=2, /* 24 FPS | */
|
|
GOPRO_FRAME_RATE_25=3, /* 25 FPS | */
|
|
GOPRO_FRAME_RATE_30=4, /* 30 FPS | */
|
|
GOPRO_FRAME_RATE_48=5, /* 48 FPS | */
|
|
GOPRO_FRAME_RATE_50=6, /* 50 FPS | */
|
|
GOPRO_FRAME_RATE_60=7, /* 60 FPS | */
|
|
GOPRO_FRAME_RATE_80=8, /* 80 FPS | */
|
|
GOPRO_FRAME_RATE_90=9, /* 90 FPS | */
|
|
GOPRO_FRAME_RATE_100=10, /* 100 FPS | */
|
|
GOPRO_FRAME_RATE_120=11, /* 120 FPS | */
|
|
GOPRO_FRAME_RATE_240=12, /* 240 FPS | */
|
|
GOPRO_FRAME_RATE_12_5=13, /* 12.5 FPS | */
|
|
GOPRO_FRAME_RATE_ENUM_END=14, /* | */
|
|
} GOPRO_FRAME_RATE;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_FIELD_OF_VIEW
|
|
#define HAVE_ENUM_GOPRO_FIELD_OF_VIEW
|
|
typedef enum GOPRO_FIELD_OF_VIEW
|
|
{
|
|
GOPRO_FIELD_OF_VIEW_WIDE=0, /* 0x00: Wide | */
|
|
GOPRO_FIELD_OF_VIEW_MEDIUM=1, /* 0x01: Medium | */
|
|
GOPRO_FIELD_OF_VIEW_NARROW=2, /* 0x02: Narrow | */
|
|
GOPRO_FIELD_OF_VIEW_ENUM_END=3, /* | */
|
|
} GOPRO_FIELD_OF_VIEW;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_VIDEO_SETTINGS_FLAGS
|
|
#define HAVE_ENUM_GOPRO_VIDEO_SETTINGS_FLAGS
|
|
typedef enum GOPRO_VIDEO_SETTINGS_FLAGS
|
|
{
|
|
GOPRO_VIDEO_SETTINGS_TV_MODE=1, /* 0=NTSC, 1=PAL | */
|
|
GOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END=2, /* | */
|
|
} GOPRO_VIDEO_SETTINGS_FLAGS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_PHOTO_RESOLUTION
|
|
#define HAVE_ENUM_GOPRO_PHOTO_RESOLUTION
|
|
typedef enum GOPRO_PHOTO_RESOLUTION
|
|
{
|
|
GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM=0, /* 5MP Medium | */
|
|
GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM=1, /* 7MP Medium | */
|
|
GOPRO_PHOTO_RESOLUTION_7MP_WIDE=2, /* 7MP Wide | */
|
|
GOPRO_PHOTO_RESOLUTION_10MP_WIDE=3, /* 10MP Wide | */
|
|
GOPRO_PHOTO_RESOLUTION_12MP_WIDE=4, /* 12MP Wide | */
|
|
GOPRO_PHOTO_RESOLUTION_ENUM_END=5, /* | */
|
|
} GOPRO_PHOTO_RESOLUTION;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_PROTUNE_WHITE_BALANCE
|
|
#define HAVE_ENUM_GOPRO_PROTUNE_WHITE_BALANCE
|
|
typedef enum GOPRO_PROTUNE_WHITE_BALANCE
|
|
{
|
|
GOPRO_PROTUNE_WHITE_BALANCE_AUTO=0, /* Auto | */
|
|
GOPRO_PROTUNE_WHITE_BALANCE_3000K=1, /* 3000K | */
|
|
GOPRO_PROTUNE_WHITE_BALANCE_5500K=2, /* 5500K | */
|
|
GOPRO_PROTUNE_WHITE_BALANCE_6500K=3, /* 6500K | */
|
|
GOPRO_PROTUNE_WHITE_BALANCE_RAW=4, /* Camera Raw | */
|
|
GOPRO_PROTUNE_WHITE_BALANCE_ENUM_END=5, /* | */
|
|
} GOPRO_PROTUNE_WHITE_BALANCE;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_PROTUNE_COLOUR
|
|
#define HAVE_ENUM_GOPRO_PROTUNE_COLOUR
|
|
typedef enum GOPRO_PROTUNE_COLOUR
|
|
{
|
|
GOPRO_PROTUNE_COLOUR_STANDARD=0, /* Auto | */
|
|
GOPRO_PROTUNE_COLOUR_NEUTRAL=1, /* Neutral | */
|
|
GOPRO_PROTUNE_COLOUR_ENUM_END=2, /* | */
|
|
} GOPRO_PROTUNE_COLOUR;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_PROTUNE_GAIN
|
|
#define HAVE_ENUM_GOPRO_PROTUNE_GAIN
|
|
typedef enum GOPRO_PROTUNE_GAIN
|
|
{
|
|
GOPRO_PROTUNE_GAIN_400=0, /* ISO 400 | */
|
|
GOPRO_PROTUNE_GAIN_800=1, /* ISO 800 (Only Hero 4) | */
|
|
GOPRO_PROTUNE_GAIN_1600=2, /* ISO 1600 | */
|
|
GOPRO_PROTUNE_GAIN_3200=3, /* ISO 3200 (Only Hero 4) | */
|
|
GOPRO_PROTUNE_GAIN_6400=4, /* ISO 6400 | */
|
|
GOPRO_PROTUNE_GAIN_ENUM_END=5, /* | */
|
|
} GOPRO_PROTUNE_GAIN;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_PROTUNE_SHARPNESS
|
|
#define HAVE_ENUM_GOPRO_PROTUNE_SHARPNESS
|
|
typedef enum GOPRO_PROTUNE_SHARPNESS
|
|
{
|
|
GOPRO_PROTUNE_SHARPNESS_LOW=0, /* Low Sharpness | */
|
|
GOPRO_PROTUNE_SHARPNESS_MEDIUM=1, /* Medium Sharpness | */
|
|
GOPRO_PROTUNE_SHARPNESS_HIGH=2, /* High Sharpness | */
|
|
GOPRO_PROTUNE_SHARPNESS_ENUM_END=3, /* | */
|
|
} GOPRO_PROTUNE_SHARPNESS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_PROTUNE_EXPOSURE
|
|
#define HAVE_ENUM_GOPRO_PROTUNE_EXPOSURE
|
|
typedef enum GOPRO_PROTUNE_EXPOSURE
|
|
{
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_5_0=0, /* -5.0 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_4_5=1, /* -4.5 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_4_0=2, /* -4.0 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_3_5=3, /* -3.5 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_3_0=4, /* -3.0 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_2_5=5, /* -2.5 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_2_0=6, /* -2.0 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_1_5=7, /* -1.5 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_1_0=8, /* -1.0 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_NEG_0_5=9, /* -0.5 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_ZERO=10, /* 0.0 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_0_5=11, /* +0.5 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_1_0=12, /* +1.0 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_1_5=13, /* +1.5 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_2_0=14, /* +2.0 EV | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_2_5=15, /* +2.5 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_3_0=16, /* +3.0 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_3_5=17, /* +3.5 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_4_0=18, /* +4.0 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_4_5=19, /* +4.5 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_POS_5_0=20, /* +5.0 EV (Hero 3+ Only) | */
|
|
GOPRO_PROTUNE_EXPOSURE_ENUM_END=21, /* | */
|
|
} GOPRO_PROTUNE_EXPOSURE;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_CHARGING
|
|
#define HAVE_ENUM_GOPRO_CHARGING
|
|
typedef enum GOPRO_CHARGING
|
|
{
|
|
GOPRO_CHARGING_DISABLED=0, /* Charging disabled | */
|
|
GOPRO_CHARGING_ENABLED=1, /* Charging enabled | */
|
|
GOPRO_CHARGING_ENUM_END=2, /* | */
|
|
} GOPRO_CHARGING;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_MODEL
|
|
#define HAVE_ENUM_GOPRO_MODEL
|
|
typedef enum GOPRO_MODEL
|
|
{
|
|
GOPRO_MODEL_UNKNOWN=0, /* Unknown gopro model | */
|
|
GOPRO_MODEL_HERO_3_PLUS_SILVER=1, /* Hero 3+ Silver (HeroBus not supported by GoPro) | */
|
|
GOPRO_MODEL_HERO_3_PLUS_BLACK=2, /* Hero 3+ Black | */
|
|
GOPRO_MODEL_HERO_4_SILVER=3, /* Hero 4 Silver | */
|
|
GOPRO_MODEL_HERO_4_BLACK=4, /* Hero 4 Black | */
|
|
GOPRO_MODEL_ENUM_END=5, /* | */
|
|
} GOPRO_MODEL;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_GOPRO_BURST_RATE
|
|
#define HAVE_ENUM_GOPRO_BURST_RATE
|
|
typedef enum GOPRO_BURST_RATE
|
|
{
|
|
GOPRO_BURST_RATE_3_IN_1_SECOND=0, /* 3 Shots / 1 Second | */
|
|
GOPRO_BURST_RATE_5_IN_1_SECOND=1, /* 5 Shots / 1 Second | */
|
|
GOPRO_BURST_RATE_10_IN_1_SECOND=2, /* 10 Shots / 1 Second | */
|
|
GOPRO_BURST_RATE_10_IN_2_SECOND=3, /* 10 Shots / 2 Second | */
|
|
GOPRO_BURST_RATE_10_IN_3_SECOND=4, /* 10 Shots / 3 Second (Hero 4 Only) | */
|
|
GOPRO_BURST_RATE_30_IN_1_SECOND=5, /* 30 Shots / 1 Second | */
|
|
GOPRO_BURST_RATE_30_IN_2_SECOND=6, /* 30 Shots / 2 Second | */
|
|
GOPRO_BURST_RATE_30_IN_3_SECOND=7, /* 30 Shots / 3 Second | */
|
|
GOPRO_BURST_RATE_30_IN_6_SECOND=8, /* 30 Shots / 6 Second | */
|
|
GOPRO_BURST_RATE_ENUM_END=9, /* | */
|
|
} GOPRO_BURST_RATE;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_LED_CONTROL_PATTERN
|
|
#define HAVE_ENUM_LED_CONTROL_PATTERN
|
|
typedef enum LED_CONTROL_PATTERN
|
|
{
|
|
LED_CONTROL_PATTERN_OFF=0, /* LED patterns off (return control to regular vehicle control) | */
|
|
LED_CONTROL_PATTERN_FIRMWAREUPDATE=1, /* LEDs show pattern during firmware update | */
|
|
LED_CONTROL_PATTERN_CUSTOM=255, /* Custom Pattern using custom bytes fields | */
|
|
LED_CONTROL_PATTERN_ENUM_END=256, /* | */
|
|
} LED_CONTROL_PATTERN;
|
|
#endif
|
|
|
|
/** @brief Flags in EKF_STATUS message */
|
|
#ifndef HAVE_ENUM_EKF_STATUS_FLAGS
|
|
#define HAVE_ENUM_EKF_STATUS_FLAGS
|
|
typedef enum EKF_STATUS_FLAGS
|
|
{
|
|
EKF_ATTITUDE=1, /* set if EKF's attitude estimate is good | */
|
|
EKF_VELOCITY_HORIZ=2, /* set if EKF's horizontal velocity estimate is good | */
|
|
EKF_VELOCITY_VERT=4, /* set if EKF's vertical velocity estimate is good | */
|
|
EKF_POS_HORIZ_REL=8, /* set if EKF's horizontal position (relative) estimate is good | */
|
|
EKF_POS_HORIZ_ABS=16, /* set if EKF's horizontal position (absolute) estimate is good | */
|
|
EKF_POS_VERT_ABS=32, /* set if EKF's vertical position (absolute) estimate is good | */
|
|
EKF_POS_VERT_AGL=64, /* set if EKF's vertical position (above ground) estimate is good | */
|
|
EKF_CONST_POS_MODE=128, /* EKF is in constant position mode and does not know it's absolute or relative position | */
|
|
EKF_PRED_POS_HORIZ_REL=256, /* set if EKF's predicted horizontal position (relative) estimate is good | */
|
|
EKF_PRED_POS_HORIZ_ABS=512, /* set if EKF's predicted horizontal position (absolute) estimate is good | */
|
|
EKF_STATUS_FLAGS_ENUM_END=513, /* | */
|
|
} EKF_STATUS_FLAGS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_MAG_CAL_STATUS
|
|
#define HAVE_ENUM_MAG_CAL_STATUS
|
|
typedef enum MAG_CAL_STATUS
|
|
{
|
|
MAG_CAL_NOT_STARTED=0, /* | */
|
|
MAG_CAL_WAITING_TO_START=1, /* | */
|
|
MAG_CAL_RUNNING_STEP_ONE=2, /* | */
|
|
MAG_CAL_RUNNING_STEP_TWO=3, /* | */
|
|
MAG_CAL_SUCCESS=4, /* | */
|
|
MAG_CAL_FAILED=5, /* | */
|
|
MAG_CAL_STATUS_ENUM_END=6, /* | */
|
|
} MAG_CAL_STATUS;
|
|
#endif
|
|
|
|
/** @brief */
|
|
#ifndef HAVE_ENUM_PID_TUNING_AXIS
|
|
#define HAVE_ENUM_PID_TUNING_AXIS
|
|
typedef enum PID_TUNING_AXIS
|
|
{
|
|
PID_TUNING_ROLL=1, /* | */
|
|
PID_TUNING_PITCH=2, /* | */
|
|
PID_TUNING_YAW=3, /* | */
|
|
PID_TUNING_AXIS_ENUM_END=4, /* | */
|
|
} PID_TUNING_AXIS;
|
|
#endif
|
|
|
|
/** @brief Special ACK block numbers control activation of dataflash log streaming */
|
|
#ifndef HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
|
|
#define HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
|
|
typedef enum MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
|
|
{
|
|
MAV_REMOTE_LOG_DATA_BLOCK_STOP=2147483645, /* UAV to stop sending DataFlash blocks | */
|
|
MAV_REMOTE_LOG_DATA_BLOCK_START=2147483646, /* UAV to start sending DataFlash blocks | */
|
|
MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS_ENUM_END=2147483647, /* | */
|
|
} MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS;
|
|
#endif
|
|
|
|
/** @brief Possible remote log data block statuses */
|
|
#ifndef HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
|
|
#define HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
|
|
typedef enum MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
|
|
{
|
|
MAV_REMOTE_LOG_DATA_BLOCK_NACK=0, /* This block has NOT been received | */
|
|
MAV_REMOTE_LOG_DATA_BLOCK_ACK=1, /* This block has been received | */
|
|
MAV_REMOTE_LOG_DATA_BLOCK_STATUSES_ENUM_END=2, /* | */
|
|
} MAV_REMOTE_LOG_DATA_BLOCK_STATUSES;
|
|
#endif
|
|
|
|
#include "../common/common.h"
|
|
|
|
// MAVLINK VERSION
|
|
|
|
#ifndef MAVLINK_VERSION
|
|
#define MAVLINK_VERSION 2
|
|
#endif
|
|
|
|
#if (MAVLINK_VERSION == 0)
|
|
#undef MAVLINK_VERSION
|
|
#define MAVLINK_VERSION 2
|
|
#endif
|
|
|
|
// MESSAGE DEFINITIONS
|
|
#include "./mavlink_msg_sensor_offsets.h"
|
|
#include "./mavlink_msg_set_mag_offsets.h"
|
|
#include "./mavlink_msg_meminfo.h"
|
|
#include "./mavlink_msg_ap_adc.h"
|
|
#include "./mavlink_msg_digicam_configure.h"
|
|
#include "./mavlink_msg_digicam_control.h"
|
|
#include "./mavlink_msg_mount_configure.h"
|
|
#include "./mavlink_msg_mount_control.h"
|
|
#include "./mavlink_msg_mount_status.h"
|
|
#include "./mavlink_msg_fence_point.h"
|
|
#include "./mavlink_msg_fence_fetch_point.h"
|
|
#include "./mavlink_msg_fence_status.h"
|
|
#include "./mavlink_msg_ahrs.h"
|
|
#include "./mavlink_msg_simstate.h"
|
|
#include "./mavlink_msg_hwstatus.h"
|
|
#include "./mavlink_msg_radio.h"
|
|
#include "./mavlink_msg_limits_status.h"
|
|
#include "./mavlink_msg_wind.h"
|
|
#include "./mavlink_msg_data16.h"
|
|
#include "./mavlink_msg_data32.h"
|
|
#include "./mavlink_msg_data64.h"
|
|
#include "./mavlink_msg_data96.h"
|
|
#include "./mavlink_msg_rangefinder.h"
|
|
#include "./mavlink_msg_airspeed_autocal.h"
|
|
#include "./mavlink_msg_rally_point.h"
|
|
#include "./mavlink_msg_rally_fetch_point.h"
|
|
#include "./mavlink_msg_compassmot_status.h"
|
|
#include "./mavlink_msg_ahrs2.h"
|
|
#include "./mavlink_msg_camera_status.h"
|
|
#include "./mavlink_msg_camera_feedback.h"
|
|
#include "./mavlink_msg_battery2.h"
|
|
#include "./mavlink_msg_ahrs3.h"
|
|
#include "./mavlink_msg_autopilot_version_request.h"
|
|
#include "./mavlink_msg_remote_log_data_block.h"
|
|
#include "./mavlink_msg_remote_log_block_status.h"
|
|
#include "./mavlink_msg_led_control.h"
|
|
#include "./mavlink_msg_mag_cal_progress.h"
|
|
#include "./mavlink_msg_mag_cal_report.h"
|
|
#include "./mavlink_msg_ekf_status_report.h"
|
|
#include "./mavlink_msg_pid_tuning.h"
|
|
#include "./mavlink_msg_gimbal_report.h"
|
|
#include "./mavlink_msg_gimbal_control.h"
|
|
#include "./mavlink_msg_gimbal_torque_cmd_report.h"
|
|
#include "./mavlink_msg_gopro_heartbeat.h"
|
|
#include "./mavlink_msg_gopro_get_request.h"
|
|
#include "./mavlink_msg_gopro_get_response.h"
|
|
#include "./mavlink_msg_gopro_set_request.h"
|
|
#include "./mavlink_msg_gopro_set_response.h"
|
|
#include "./mavlink_msg_gps_accuracy.h"
|
|
|
|
#ifdef __cplusplus
|
|
}
|
|
#endif // __cplusplus
|
|
#endif // MAVLINK_ARDUPILOTMEGA_H
|