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_AUTO_ENABLED=4,/* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
MAV_MODE_FLAG_STABILIZE_ENABLED=16,/* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
MAV_MODE_FLAG_HIL_ENABLED=32,/* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
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_ENUM_END=129,/* | */
};
#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. */
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_TEST_DISARMED=66,/* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
MAV_MODE_STABILIZE_DISARMED=80,/* System is allowed to be active, under assisted RC control. | */
MAV_MODE_GUIDED_DISARMED=88,/* System is allowed to be active, under autonomous control, manual setpoint | */
MAV_MODE_AUTO_DISARMED=92,/* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
MAV_MODE_MANUAL_ARMED=192,/* System is allowed to be active, under manual (RC) control, no stabilization | */
MAV_MODE_TEST_ARMED=194,/* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
MAV_MODE_STABILIZE_ARMED=208,/* System is allowed to be active, under assisted RC control. | */
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_ENUM_END=221,/* | */
};
#endif
/** @brief */
#ifndef HAVE_ENUM_MAV_STATE
#define HAVE_ENUM_MAV_STATE
enumMAV_STATE
{
MAV_STATE_UNINIT=0,/* Uninitialized system, state is unknown. | */
MAV_STATE_BOOT=1,/* System is booting up. | */
MAV_STATE_CALIBRATING=2,/* System is calibrating and not flight-ready. | */
MAV_STATE_STANDBY=3,/* System is grounded and on standby. It can be launched any time. | */
MAV_STATE_ACTIVE=4,/* System is active and might be already airborne. Motors are engaged. | */
MAV_STATE_CRITICAL=5,/* System is in a non-normal flight mode. It can however still navigate. | */
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_ENUM_END=8,/* | */
};
#endif
/** @brief */
#ifndef HAVE_ENUM_MAV_COMPONENT
#define HAVE_ENUM_MAV_COMPONENT
enumMAV_COMPONENT
{
MAV_COMP_ID_ALL=0,/* | */
MAV_COMP_ID_CAMERA=100,/* | */
MAV_COMP_ID_SERVO1=140,/* | */
MAV_COMP_ID_SERVO2=141,/* | */
MAV_COMP_ID_SERVO3=142,/* | */
MAV_COMP_ID_SERVO4=143,/* | */
MAV_COMP_ID_SERVO5=144,/* | */
MAV_COMP_ID_SERVO6=145,/* | */
MAV_COMP_ID_SERVO7=146,/* | */
MAV_COMP_ID_SERVO8=147,/* | */
MAV_COMP_ID_SERVO9=148,/* | */
MAV_COMP_ID_SERVO10=149,/* | */
MAV_COMP_ID_SERVO11=150,/* | */
MAV_COMP_ID_SERVO12=151,/* | */
MAV_COMP_ID_SERVO13=152,/* | */
MAV_COMP_ID_SERVO14=153,/* | */
MAV_COMP_ID_MAPPER=180,/* | */
MAV_COMP_ID_MISSIONPLANNER=190,/* | */
MAV_COMP_ID_PATHPLANNER=195,/* | */
MAV_COMP_ID_IMU=200,/* | */
MAV_COMP_ID_IMU_2=201,/* | */
MAV_COMP_ID_IMU_3=202,/* | */
MAV_COMP_ID_GPS=220,/* | */
MAV_COMP_ID_UDP_BRIDGE=240,/* | */
MAV_COMP_ID_UART_BRIDGE=241,/* | */
MAV_COMP_ID_SYSTEM_CONTROL=250,/* | */
MAV_COMPONENT_ENUM_END=251,/* | */
};
#endif
/** @brief */
#ifndef HAVE_ENUM_MAV_FRAME
#define HAVE_ENUM_MAV_FRAME
enumMAV_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_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_ROI_WPNEXT=1,/* Point toward next MISSION. | */
MAV_ROI_WPINDEX=2,/* Point toward given MISSION. | */
MAV_ROI_LOCATION=3,/* Point toward fixed location. | */
MAV_ROI_TARGET=4,/* Point toward of given id. | */
MAV_ROI_ENUM_END=5,/* | */
};
#endif
/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */
#ifndef HAVE_ENUM_MAV_CMD_ACK
#define HAVE_ENUM_MAV_CMD_ACK
enumMAV_CMD_ACK
{
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_ACCESS_DENIED=3,/* The system is refusing to accept this command from this source / communication partner. | */
MAV_CMD_ACK_ERR_NOT_SUPPORTED=4,/* Command or mission item is not supported, other commands would be accepted. | */
MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5,/* The coordinate frame of this command / mission item is not supported. | */
MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6,/* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */
MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7,/* The X or latitude 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_ENUM_END=10,/* | */
};
#endif
/** @brief result from a mavlink command */
#ifndef HAVE_ENUM_MAV_RESULT
#define HAVE_ENUM_MAV_RESULT
enumMAV_RESULT
{
MAV_RESULT_ACCEPTED=0,/* Command ACCEPTED and EXECUTED | */
MAV_RESULT_FAILED=4,/* Command executed, but failed | */
MAV_RESULT_ENUM_END=5,/* | */
};
#endif
/** @brief result in a mavlink mission ack */
#ifndef HAVE_ENUM_MAV_MISSION_RESULT
#define HAVE_ENUM_MAV_MISSION_RESULT
enumMAV_MISSION_RESULT
{
MAV_MISSION_ACCEPTED=0,/* mission accepted OK | */
MAV_MISSION_ERROR=1,/* generic error / not accepting mission commands at all right now | */
MAV_MISSION_UNSUPPORTED_FRAME=2,/* coordinate frame is not supported | */
MAV_MISSION_UNSUPPORTED=3,/* command is not supported | */
MAV_MISSION_NO_SPACE=4,/* mission item exceeds storage space | */
MAV_MISSION_INVALID=5,/* one of the parameters has an invalid value | */
MAV_MISSION_INVALID_PARAM1=6,/* param1 has an invalid value | */
MAV_MISSION_INVALID_PARAM2=7,/* param2 has an invalid value | */
MAV_MISSION_INVALID_PARAM3=8,/* param3 has an invalid value | */
MAV_MISSION_INVALID_PARAM4=9,/* param4 has an invalid value | */
MAV_MISSION_INVALID_PARAM5_X=10,/* x/param5 has an invalid value | */
MAV_MISSION_INVALID_PARAM6_Y=11,/* y/param6 has an invalid value | */
MAV_MISSION_INVALID_PARAM7=12,/* param7 has an invalid value | */
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_RESULT_ENUM_END=15,/* | */
};
#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/. */
#ifndef HAVE_ENUM_MAV_SEVERITY
#define HAVE_ENUM_MAV_SEVERITY
enumMAV_SEVERITY
{
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_CRITICAL=2,/* Action must be taken immediately. Indicates failure in a primary system. | */
MAV_SEVERITY_ERROR=3,/* Indicates an error in secondary/redundant systems. | */
MAV_SEVERITY_WARNING=4,/* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */
MAV_SEVERITY_NOTICE=5,/* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */
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. | */