/** @brief Flags to indicate the status of camera storage. */
#ifndef HAVE_ENUM_STORAGE_STATUS
#define HAVE_ENUM_STORAGE_STATUS
typedefenumSTORAGE_STATUS
{
STORAGE_STATUS_EMPTY=0,/* Storage is missing (no microSD card loaded for example.) | */
STORAGE_STATUS_UNFORMATTED=1,/* Storage present but unformatted. | */
STORAGE_STATUS_READY=2,/* Storage present and ready. | */
STORAGE_STATUS_NOT_SUPPORTED=3,/* Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored. | */
STORAGE_STATUS_ENUM_END=4,/* | */
}STORAGE_STATUS;
#endif
/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */
#ifndef HAVE_ENUM_MAV_CMD
#define HAVE_ENUM_MAV_CMD
...
...
@@ -481,6 +494,7 @@ typedef enum MAV_CMD
MAV_CMD_VIDEO_START_STREAMING=2502,/* Start video streaming |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_VIDEO_STOP_STREAMING=2503,/* Stop the given video stream |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION=2504,/* Request video stream information (VIDEO_STREAM_INFORMATION) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_REQUEST_VIDEO_STREAM_STATUS=2505,/* Request video stream status (VIDEO_STREAM_STATUS) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_LOGGING_START=2510,/* Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) |Format: 0: ULog| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
MAV_CMD_LOGGING_STOP=2511,/* Request to stop streaming log data over MAVLink |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
MAV_CMD_AIRFRAME_CONFIGURATION=2520,/* |Landing gear ID (default: 0, -1 for all)| Landing gear position (Down: 0, Up: 1, NAN for no change)| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| */
uint16_tcog;/*< [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_tfix_type;/*< See the GPS_FIX_TYPE enum.*/
uint8_tsatellites_visible;/*< Number of satellites visible. If unknown, set to 255*/
}mavlink_gps_raw_int_t;
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
int32_talt_ellipsoid;/*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/
uint16_tyaw;/*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @return length of the message in bytes (excluding serial stream start sign)
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @return length of the message in bytes (excluding serial stream start sign)
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.