Browse Source

GCS_MAVLink: regenerated MAVLink headers

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
5d2d6e0063
  1. 69
      libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
  2. 2
      libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h
  3. 128
      libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h
  4. 10
      libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
  5. 2
      libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h

69
libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h

@ -30,24 +30,10 @@ extern "C" {
// ENUM DEFINITIONS // ENUM DEFINITIONS
/** @brief Enumeration of possible mount operation modes */
#ifndef HAVE_ENUM_MAV_MOUNT_MODE
#define HAVE_ENUM_MAV_MOUNT_MODE
enum MAV_MOUNT_MODE
{
MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
MAV_MOUNT_MODE_ENUM_END=5, /* | */
};
#endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MAV_CMD #ifndef HAVE_ENUM_MAV_CMD
#define HAVE_ENUM_MAV_CMD #define HAVE_ENUM_MAV_CMD
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_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_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| */
@ -79,11 +65,12 @@ enum MAV_CMD
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_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_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_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(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| 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_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_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, See PARACHUTE_ACTION enum)| 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_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_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| 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_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_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| 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_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| 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| */
@ -94,39 +81,13 @@ enum MAV_CMD
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ 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_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
MAV_CMD_ENUM_END=501, /* | */ MAV_CMD_ENUM_END=501, /* | */
}; } MAV_CMD;
#endif
/** @brief */
#ifndef HAVE_ENUM_FENCE_ACTION
#define HAVE_ENUM_FENCE_ACTION
enum FENCE_ACTION
{
FENCE_ACTION_NONE=0, /* Disable fenced mode | */
FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */
FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */
FENCE_ACTION_ENUM_END=4, /* | */
};
#endif
/** @brief */
#ifndef HAVE_ENUM_FENCE_BREACH
#define HAVE_ENUM_FENCE_BREACH
enum FENCE_BREACH
{
FENCE_BREACH_NONE=0, /* No last fence breach | */
FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */
FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
FENCE_BREACH_ENUM_END=4, /* | */
};
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_LIMITS_STATE #ifndef HAVE_ENUM_LIMITS_STATE
#define HAVE_ENUM_LIMITS_STATE #define HAVE_ENUM_LIMITS_STATE
enum LIMITS_STATE typedef enum LIMITS_STATE
{ {
LIMITS_INIT=0, /* pre-initialization | */ LIMITS_INIT=0, /* pre-initialization | */
LIMITS_DISABLED=1, /* disabled | */ LIMITS_DISABLED=1, /* disabled | */
@ -135,54 +96,54 @@ enum LIMITS_STATE
LIMITS_RECOVERING=4, /* taking action eg. RTL | */ LIMITS_RECOVERING=4, /* taking action eg. RTL | */
LIMITS_RECOVERED=5, /* we're no longer in breach of a limit | */ LIMITS_RECOVERED=5, /* we're no longer in breach of a limit | */
LIMITS_STATE_ENUM_END=6, /* | */ LIMITS_STATE_ENUM_END=6, /* | */
}; } LIMITS_STATE;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_LIMIT_MODULE #ifndef HAVE_ENUM_LIMIT_MODULE
#define HAVE_ENUM_LIMIT_MODULE #define HAVE_ENUM_LIMIT_MODULE
enum LIMIT_MODULE typedef enum LIMIT_MODULE
{ {
LIMIT_GPSLOCK=1, /* pre-initialization | */ LIMIT_GPSLOCK=1, /* pre-initialization | */
LIMIT_GEOFENCE=2, /* disabled | */ LIMIT_GEOFENCE=2, /* disabled | */
LIMIT_ALTITUDE=4, /* checking limits | */ LIMIT_ALTITUDE=4, /* checking limits | */
LIMIT_MODULE_ENUM_END=5, /* | */ LIMIT_MODULE_ENUM_END=5, /* | */
}; } LIMIT_MODULE;
#endif #endif
/** @brief Flags in RALLY_POINT message */ /** @brief Flags in RALLY_POINT message */
#ifndef HAVE_ENUM_RALLY_FLAGS #ifndef HAVE_ENUM_RALLY_FLAGS
#define HAVE_ENUM_RALLY_FLAGS #define HAVE_ENUM_RALLY_FLAGS
enum RALLY_FLAGS typedef enum RALLY_FLAGS
{ {
FAVORABLE_WIND=1, /* Flag set when requiring favorable winds for landing. | */ 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. | */ 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_ENUM_END=3, /* | */
}; } RALLY_FLAGS;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_PARACHUTE_ACTION #ifndef HAVE_ENUM_PARACHUTE_ACTION
#define HAVE_ENUM_PARACHUTE_ACTION #define HAVE_ENUM_PARACHUTE_ACTION
enum PARACHUTE_ACTION typedef enum PARACHUTE_ACTION
{ {
PARACHUTE_DISABLE=0, /* Disable parachute release | */ PARACHUTE_DISABLE=0, /* Disable parachute release | */
PARACHUTE_ENABLE=1, /* Enable parachute release | */ PARACHUTE_ENABLE=1, /* Enable parachute release | */
PARACHUTE_RELEASE=2, /* Release parachute | */ PARACHUTE_RELEASE=2, /* Release parachute | */
PARACHUTE_ACTION_ENUM_END=3, /* | */ PARACHUTE_ACTION_ENUM_END=3, /* | */
}; } PARACHUTE_ACTION;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE #ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE
#define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE #define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE
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_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_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_PILOT=2, /* throttle pass-through from pilot's transmitter | */
MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */ MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */
}; } MOTOR_TEST_THROTTLE_TYPE;
#endif #endif
#include "../common/common.h" #include "../common/common.h"

2
libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Apr 28 12:26:15 2014" #define MAVLINK_BUILD_DATE "Thu May 15 17:09:52 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

128
libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h

@ -33,7 +33,7 @@ extern "C" {
/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ /** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */
#ifndef HAVE_ENUM_MAV_AUTOPILOT #ifndef HAVE_ENUM_MAV_AUTOPILOT
#define HAVE_ENUM_MAV_AUTOPILOT #define HAVE_ENUM_MAV_AUTOPILOT
enum MAV_AUTOPILOT typedef enum MAV_AUTOPILOT
{ {
MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */ MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */
@ -53,13 +53,13 @@ enum MAV_AUTOPILOT
MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */
MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */
MAV_AUTOPILOT_ENUM_END=17, /* | */ MAV_AUTOPILOT_ENUM_END=17, /* | */
}; } MAV_AUTOPILOT;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MAV_TYPE #ifndef HAVE_ENUM_MAV_TYPE
#define HAVE_ENUM_MAV_TYPE #define HAVE_ENUM_MAV_TYPE
enum MAV_TYPE typedef enum MAV_TYPE
{ {
MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
@ -81,13 +81,13 @@ enum MAV_TYPE
MAV_TYPE_KITE=17, /* Flapping wing | */ MAV_TYPE_KITE=17, /* Flapping wing | */
MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
MAV_TYPE_ENUM_END=19, /* | */ MAV_TYPE_ENUM_END=19, /* | */
}; } MAV_TYPE;
#endif #endif
/** @brief These flags encode the MAV mode. */ /** @brief These flags encode the MAV mode. */
#ifndef HAVE_ENUM_MAV_MODE_FLAG #ifndef HAVE_ENUM_MAV_MODE_FLAG
#define HAVE_ENUM_MAV_MODE_FLAG #define HAVE_ENUM_MAV_MODE_FLAG
enum MAV_MODE_FLAG typedef enum MAV_MODE_FLAG
{ {
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
@ -98,13 +98,13 @@ enum MAV_MODE_FLAG
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
MAV_MODE_FLAG_ENUM_END=129, /* | */ MAV_MODE_FLAG_ENUM_END=129, /* | */
}; } MAV_MODE_FLAG;
#endif #endif
/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ /** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */
#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION #ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION #define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
enum MAV_MODE_FLAG_DECODE_POSITION typedef enum MAV_MODE_FLAG_DECODE_POSITION
{ {
MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
@ -115,27 +115,27 @@ enum MAV_MODE_FLAG_DECODE_POSITION
MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */
MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */
}; } MAV_MODE_FLAG_DECODE_POSITION;
#endif #endif
/** @brief Override command, pauses current mission execution and moves immediately to a position */ /** @brief Override command, pauses current mission execution and moves immediately to a position */
#ifndef HAVE_ENUM_MAV_GOTO #ifndef HAVE_ENUM_MAV_GOTO
#define HAVE_ENUM_MAV_GOTO #define HAVE_ENUM_MAV_GOTO
enum MAV_GOTO typedef enum MAV_GOTO
{ {
MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */
MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */
MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */
MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */
MAV_GOTO_ENUM_END=4, /* | */ MAV_GOTO_ENUM_END=4, /* | */
}; } MAV_GOTO;
#endif #endif
/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it /** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it
simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */
#ifndef HAVE_ENUM_MAV_MODE #ifndef HAVE_ENUM_MAV_MODE
#define HAVE_ENUM_MAV_MODE #define HAVE_ENUM_MAV_MODE
enum MAV_MODE typedef enum MAV_MODE
{ {
MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */
MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */
@ -149,13 +149,13 @@ enum MAV_MODE
MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */
MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
MAV_MODE_ENUM_END=221, /* | */ MAV_MODE_ENUM_END=221, /* | */
}; } MAV_MODE;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MAV_STATE #ifndef HAVE_ENUM_MAV_STATE
#define HAVE_ENUM_MAV_STATE #define HAVE_ENUM_MAV_STATE
enum MAV_STATE typedef enum MAV_STATE
{ {
MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
MAV_STATE_BOOT=1, /* System is booting up. | */ MAV_STATE_BOOT=1, /* System is booting up. | */
@ -166,13 +166,13 @@ enum MAV_STATE
MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */
MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
MAV_STATE_ENUM_END=8, /* | */ MAV_STATE_ENUM_END=8, /* | */
}; } MAV_STATE;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MAV_COMPONENT #ifndef HAVE_ENUM_MAV_COMPONENT
#define HAVE_ENUM_MAV_COMPONENT #define HAVE_ENUM_MAV_COMPONENT
enum MAV_COMPONENT typedef enum MAV_COMPONENT
{ {
MAV_COMP_ID_ALL=0, /* | */ MAV_COMP_ID_ALL=0, /* | */
MAV_COMP_ID_CAMERA=100, /* | */ MAV_COMP_ID_CAMERA=100, /* | */
@ -201,13 +201,13 @@ enum MAV_COMPONENT
MAV_COMP_ID_UART_BRIDGE=241, /* | */ MAV_COMP_ID_UART_BRIDGE=241, /* | */
MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */
MAV_COMPONENT_ENUM_END=251, /* | */ MAV_COMPONENT_ENUM_END=251, /* | */
}; } MAV_COMPONENT;
#endif #endif
/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ /** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */
#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR #ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR
#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR #define HAVE_ENUM_MAV_SYS_STATUS_SENSOR
enum MAV_SYS_STATUS_SENSOR typedef enum MAV_SYS_STATUS_SENSOR
{ {
MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */
MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */
@ -231,27 +231,29 @@ enum MAV_SYS_STATUS_SENSOR
MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */
MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */
MAV_SYS_STATUS_SENSOR_ENUM_END=1048577, /* | */ MAV_SYS_STATUS_SENSOR_ENUM_END=1048577, /* | */
}; } MAV_SYS_STATUS_SENSOR;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MAV_FRAME #ifndef HAVE_ENUM_MAV_FRAME
#define HAVE_ENUM_MAV_FRAME #define HAVE_ENUM_MAV_FRAME
enum MAV_FRAME typedef enum MAV_FRAME
{ {
MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */
MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */
MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */
MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */
MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */
MAV_FRAME_ENUM_END=5, /* | */ MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame with some fields as scaled integers, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | */
}; MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame with some fields as scaled integers, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | */
MAV_FRAME_ENUM_END=7, /* | */
} MAV_FRAME;
#endif #endif
/** @brief */ /** @brief */
#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE #ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE
#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE #define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE
enum MAVLINK_DATA_STREAM_TYPE typedef enum MAVLINK_DATA_STREAM_TYPE
{ {
MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */
MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */
@ -260,7 +262,47 @@ enum MAVLINK_DATA_STREAM_TYPE
MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */
MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */
MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */
}; } MAVLINK_DATA_STREAM_TYPE;
#endif
/** @brief */
#ifndef HAVE_ENUM_FENCE_ACTION
#define HAVE_ENUM_FENCE_ACTION
typedef enum FENCE_ACTION
{
FENCE_ACTION_NONE=0, /* Disable fenced mode | */
FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */
FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */
FENCE_ACTION_ENUM_END=4, /* | */
} FENCE_ACTION;
#endif
/** @brief */
#ifndef HAVE_ENUM_FENCE_BREACH
#define HAVE_ENUM_FENCE_BREACH
typedef enum FENCE_BREACH
{
FENCE_BREACH_NONE=0, /* No last fence breach | */
FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */
FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
FENCE_BREACH_ENUM_END=4, /* | */
} FENCE_BREACH;
#endif
/** @brief Enumeration of possible mount operation modes */
#ifndef HAVE_ENUM_MAV_MOUNT_MODE
#define HAVE_ENUM_MAV_MOUNT_MODE
typedef enum MAV_MOUNT_MODE
{
MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */
MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */
MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
MAV_MOUNT_MODE_ENUM_END=5, /* | */
} MAV_MOUNT_MODE;
#endif #endif
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a
@ -268,7 +310,7 @@ enum MAVLINK_DATA_STREAM_TYPE
the recommended messages. */ the recommended messages. */
#ifndef HAVE_ENUM_MAV_DATA_STREAM #ifndef HAVE_ENUM_MAV_DATA_STREAM
#define HAVE_ENUM_MAV_DATA_STREAM #define HAVE_ENUM_MAV_DATA_STREAM
enum MAV_DATA_STREAM typedef enum MAV_DATA_STREAM
{ {
MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
@ -280,7 +322,7 @@ enum MAV_DATA_STREAM
MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
MAV_DATA_STREAM_ENUM_END=13, /* | */ MAV_DATA_STREAM_ENUM_END=13, /* | */
}; } MAV_DATA_STREAM;
#endif #endif
/** @brief The ROI (region of interest) for the vehicle. This can be /** @brief The ROI (region of interest) for the vehicle. This can be
@ -288,7 +330,7 @@ enum MAV_DATA_STREAM
MAV_CMD_NAV_ROI). */ MAV_CMD_NAV_ROI). */
#ifndef HAVE_ENUM_MAV_ROI #ifndef HAVE_ENUM_MAV_ROI
#define HAVE_ENUM_MAV_ROI #define HAVE_ENUM_MAV_ROI
enum MAV_ROI typedef enum MAV_ROI
{ {
MAV_ROI_NONE=0, /* No region of interest. | */ MAV_ROI_NONE=0, /* No region of interest. | */
MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */
@ -296,13 +338,13 @@ enum MAV_ROI
MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
MAV_ROI_TARGET=4, /* Point toward of given id. | */ MAV_ROI_TARGET=4, /* Point toward of given id. | */
MAV_ROI_ENUM_END=5, /* | */ MAV_ROI_ENUM_END=5, /* | */
}; } MAV_ROI;
#endif #endif
/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ /** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */
#ifndef HAVE_ENUM_MAV_CMD_ACK #ifndef HAVE_ENUM_MAV_CMD_ACK
#define HAVE_ENUM_MAV_CMD_ACK #define HAVE_ENUM_MAV_CMD_ACK
enum MAV_CMD_ACK typedef enum MAV_CMD_ACK
{ {
MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */
MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */
@ -314,13 +356,13 @@ enum MAV_CMD_ACK
MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */
MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */
MAV_CMD_ACK_ENUM_END=10, /* | */ MAV_CMD_ACK_ENUM_END=10, /* | */
}; } MAV_CMD_ACK;
#endif #endif
/** @brief Specifies the datatype of a MAVLink parameter. */ /** @brief Specifies the datatype of a MAVLink parameter. */
#ifndef HAVE_ENUM_MAV_PARAM_TYPE #ifndef HAVE_ENUM_MAV_PARAM_TYPE
#define HAVE_ENUM_MAV_PARAM_TYPE #define HAVE_ENUM_MAV_PARAM_TYPE
enum MAV_PARAM_TYPE typedef enum MAV_PARAM_TYPE
{ {
MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */
MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */
@ -333,13 +375,13 @@ enum MAV_PARAM_TYPE
MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */
MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */
MAV_PARAM_TYPE_ENUM_END=11, /* | */ MAV_PARAM_TYPE_ENUM_END=11, /* | */
}; } MAV_PARAM_TYPE;
#endif #endif
/** @brief result from a mavlink command */ /** @brief result from a mavlink command */
#ifndef HAVE_ENUM_MAV_RESULT #ifndef HAVE_ENUM_MAV_RESULT
#define HAVE_ENUM_MAV_RESULT #define HAVE_ENUM_MAV_RESULT
enum MAV_RESULT typedef enum MAV_RESULT
{ {
MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
@ -347,13 +389,13 @@ enum MAV_RESULT
MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
MAV_RESULT_FAILED=4, /* Command executed, but failed | */ MAV_RESULT_FAILED=4, /* Command executed, but failed | */
MAV_RESULT_ENUM_END=5, /* | */ MAV_RESULT_ENUM_END=5, /* | */
}; } MAV_RESULT;
#endif #endif
/** @brief result in a mavlink mission ack */ /** @brief result in a mavlink mission ack */
#ifndef HAVE_ENUM_MAV_MISSION_RESULT #ifndef HAVE_ENUM_MAV_MISSION_RESULT
#define HAVE_ENUM_MAV_MISSION_RESULT #define HAVE_ENUM_MAV_MISSION_RESULT
enum MAV_MISSION_RESULT typedef enum MAV_MISSION_RESULT
{ {
MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */
MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */
@ -371,13 +413,13 @@ enum MAV_MISSION_RESULT
MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */
MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */
MAV_MISSION_RESULT_ENUM_END=15, /* | */ MAV_MISSION_RESULT_ENUM_END=15, /* | */
}; } MAV_MISSION_RESULT;
#endif #endif
/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ /** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */
#ifndef HAVE_ENUM_MAV_SEVERITY #ifndef HAVE_ENUM_MAV_SEVERITY
#define HAVE_ENUM_MAV_SEVERITY #define HAVE_ENUM_MAV_SEVERITY
enum MAV_SEVERITY typedef enum MAV_SEVERITY
{ {
MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */
MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */
@ -388,13 +430,13 @@ enum MAV_SEVERITY
MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */
MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */
MAV_SEVERITY_ENUM_END=8, /* | */ MAV_SEVERITY_ENUM_END=8, /* | */
}; } MAV_SEVERITY;
#endif #endif
/** @brief Power supply status flags (bitmask) */ /** @brief Power supply status flags (bitmask) */
#ifndef HAVE_ENUM_MAV_POWER_STATUS #ifndef HAVE_ENUM_MAV_POWER_STATUS
#define HAVE_ENUM_MAV_POWER_STATUS #define HAVE_ENUM_MAV_POWER_STATUS
enum MAV_POWER_STATUS typedef enum MAV_POWER_STATUS
{ {
MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */
MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */
@ -403,26 +445,26 @@ enum MAV_POWER_STATUS
MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */
MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */
MAV_POWER_STATUS_ENUM_END=33, /* | */ MAV_POWER_STATUS_ENUM_END=33, /* | */
}; } MAV_POWER_STATUS;
#endif #endif
/** @brief SERIAL_CONTROL device types */ /** @brief SERIAL_CONTROL device types */
#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV #ifndef HAVE_ENUM_SERIAL_CONTROL_DEV
#define HAVE_ENUM_SERIAL_CONTROL_DEV #define HAVE_ENUM_SERIAL_CONTROL_DEV
enum SERIAL_CONTROL_DEV typedef enum SERIAL_CONTROL_DEV
{ {
SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */
SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */
SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */
SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */
SERIAL_CONTROL_DEV_ENUM_END=4, /* | */ SERIAL_CONTROL_DEV_ENUM_END=4, /* | */
}; } SERIAL_CONTROL_DEV;
#endif #endif
/** @brief SERIAL_CONTROL flags (bitmask) */ /** @brief SERIAL_CONTROL flags (bitmask) */
#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG #ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG
#define HAVE_ENUM_SERIAL_CONTROL_FLAG #define HAVE_ENUM_SERIAL_CONTROL_FLAG
enum SERIAL_CONTROL_FLAG typedef enum SERIAL_CONTROL_FLAG
{ {
SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */
SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */
@ -430,7 +472,7 @@ enum SERIAL_CONTROL_FLAG
SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */
SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */
SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */
}; } SERIAL_CONTROL_FLAG;
#endif #endif

10
libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h

@ -7,7 +7,7 @@ typedef struct __mavlink_heartbeat_t
uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags. uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags.
uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM
uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
uint8_t system_status; ///< System status flag, see MAV_STATE ENUM uint8_t system_status; ///< System status flag, see MAV_STATE ENUM
uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
} mavlink_heartbeat_t; } mavlink_heartbeat_t;
@ -41,7 +41,7 @@ typedef struct __mavlink_heartbeat_t
* *
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags. * @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM * @param system_status System status flag, see MAV_STATE ENUM
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
@ -87,7 +87,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
* @param msg The MAVLink message to compress the data into * @param msg The MAVLink message to compress the data into
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags. * @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM * @param system_status System status flag, see MAV_STATE ENUM
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint
* *
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags. * @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM * @param system_status System status flag, see MAV_STATE ENUM
*/ */
@ -268,7 +268,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_
/** /**
* @brief Get field base_mode from heartbeat message * @brief Get field base_mode from heartbeat message
* *
* @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
*/ */
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
{ {

2
libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Apr 28 12:26:15 2014" #define MAVLINK_BUILD_DATE "Thu May 15 17:09:52 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

Loading…
Cancel
Save