MAV_MODE_FLAG_SAFETY_ARMED=128,/* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64,/* 0b01000000 remote control input is enabled. | */
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_STABILIZE_ENABLED=16,/* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
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_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_RESERVED_ENABLED=1,/* 0b00000001 Reserved for future use. | */
MAV_MODE_FLAG_ENUM_END=129,/* | */
};
/** @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. */
enumMAV_MODE_FLAG_DECODE_POSITION
{
MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128,/* First bit: 10000000 | */
MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64,/* Second bit: 01000000 | */
MAV_MODE_FLAG_DECODE_POSITION_HIL=32,/* Third bit: 00100000 | */
MAV_MODE_PREFLIGHT=0,/* System is not ready to fly, booting, calibrating, etc. No flag is set. | */
MAV_MODE_STABILIZE_DISARMED=80,/* System is allowed to be active, under assisted RC control. | */
MAV_MODE_STABILIZE_ARMED=208,/* System is allowed to be active, under assisted RC control. | */
MAV_MODE_MANUAL_DISARMED=64,/* System is allowed to be active, under manual (RC) control, no stabilization | */
MAV_MODE_MANUAL_ARMED=192,/* System is allowed to be active, under manual (RC) control, no stabilization | */
MAV_MODE_GUIDED_DISARMED=88,/* 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_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_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_TEST_DISARMED=66,/* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
MAV_MODE_TEST_ARMED=194,/* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
MAV_MODE_ENUM_END=221,/* | */
};
/** @brief */
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,/* | */
};
/** @brief */
enumMAV_TYPE
{
MAV_TYPE_GENERIC=0,/* Generic micro air vehicle. | */
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_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_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_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| Empty| 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_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_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| Empty| Empty| 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_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| Reserved| 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_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,/* | */
};
/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */
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. | */