/** @brief Override command, pauses current mission execution and moves immediately to a position */
enumMAV_GOTO
{
MAV_GOTO_DO_HOLD=0,/* Hold at the current position. | */
MAV_GOTO_DO_CONTINUE=0,/* Continue with the mission execution. | */
MAV_GOTO_HOLD_AT_CURRENT_POSITION=0,/* Hold at the current position of the system | */
MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=0,/* Hold at the position specified in the parameters of the DO_HOLD action | */
MAV_GOTO_ENUM_END=1,/* | */
};
/** @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. */
enumMAV_MODE
...
...
@@ -147,6 +157,7 @@ enum MAV_TYPE
/** @brief */
enumMAV_COMPONENT
{
MAV_COMP_ID_ALL=0,/* | */
MAV_COMP_ID_GPS=220,/* | */
MAV_COMP_ID_MISSIONPLANNER=190,/* | */
MAV_COMP_ID_PATHPLANNER=195,/* | */
...
...
@@ -237,7 +248,9 @@ enum MAV_CMD
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_ENUM_END=246,/* | */
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 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_ENUM_END=253,/* | */
};
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a
<fieldtype="float"name="x">Global X position</field>
<fieldtype="float"name="y">Global Y position</field>
<fieldtype="float"name="z">Global Z position</field>
<fieldtype="float"name="roll">Roll angle in rad</field>
<fieldtype="float"name="pitch">Pitch angle in rad</field>
<fieldtype="float"name="yaw">Yaw angle in rad</field>
</message>
<!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files -->
<messageid="249"name="MEMORY_VECT">
<description>Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>