Commit c1dd0aae authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/baa1a47abe9eb32c55d286b242526946d5eb9e3d
parent 92dad4b1
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -12,7 +12,7 @@ typedef struct __mavlink_camera_image_captured_t { ...@@ -12,7 +12,7 @@ typedef struct __mavlink_camera_image_captured_t {
int32_t alt; /*< [mm] Altitude (MSL) where image was taken*/ int32_t alt; /*< [mm] Altitude (MSL) where image was taken*/
int32_t relative_alt; /*< [mm] Altitude above ground*/ int32_t relative_alt; /*< [mm] Altitude above ground*/
float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)*/ float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)*/
int32_t image_index; /*< Zero based index of this image (image count since armed -1)*/ int32_t image_index; /*< Zero based index of this image (image count -1)*/
uint8_t camera_id; /*< Camera ID (1 for first, 2 for second, etc.)*/ uint8_t camera_id; /*< Camera ID (1 for first, 2 for second, etc.)*/
int8_t capture_result; /*< Boolean indicating success (1) or failure (0) while capturing this image.*/ int8_t capture_result; /*< Boolean indicating success (1) or failure (0) while capturing this image.*/
char file_url[205]; /*< URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.*/ char file_url[205]; /*< URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.*/
...@@ -80,7 +80,7 @@ typedef struct __mavlink_camera_image_captured_t { ...@@ -80,7 +80,7 @@ typedef struct __mavlink_camera_image_captured_t {
* @param alt [mm] Altitude (MSL) where image was taken * @param alt [mm] Altitude (MSL) where image was taken
* @param relative_alt [mm] Altitude above ground * @param relative_alt [mm] Altitude above ground
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)
* @param image_index Zero based index of this image (image count since armed -1) * @param image_index Zero based index of this image (image count -1)
* @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
* @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
...@@ -136,7 +136,7 @@ static inline uint16_t mavlink_msg_camera_image_captured_pack(uint8_t system_id, ...@@ -136,7 +136,7 @@ static inline uint16_t mavlink_msg_camera_image_captured_pack(uint8_t system_id,
* @param alt [mm] Altitude (MSL) where image was taken * @param alt [mm] Altitude (MSL) where image was taken
* @param relative_alt [mm] Altitude above ground * @param relative_alt [mm] Altitude above ground
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)
* @param image_index Zero based index of this image (image count since armed -1) * @param image_index Zero based index of this image (image count -1)
* @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
* @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
...@@ -218,7 +218,7 @@ static inline uint16_t mavlink_msg_camera_image_captured_encode_chan(uint8_t sys ...@@ -218,7 +218,7 @@ static inline uint16_t mavlink_msg_camera_image_captured_encode_chan(uint8_t sys
* @param alt [mm] Altitude (MSL) where image was taken * @param alt [mm] Altitude (MSL) where image was taken
* @param relative_alt [mm] Altitude above ground * @param relative_alt [mm] Altitude above ground
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)
* @param image_index Zero based index of this image (image count since armed -1) * @param image_index Zero based index of this image (image count -1)
* @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
* @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
*/ */
...@@ -401,7 +401,7 @@ static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_mes ...@@ -401,7 +401,7 @@ static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_mes
/** /**
* @brief Get field image_index from camera_image_captured message * @brief Get field image_index from camera_image_captured message
* *
* @return Zero based index of this image (image count since armed -1) * @return Zero based index of this image (image count -1)
*/ */
static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg) static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg)
{ {
......
...@@ -8942,7 +8942,7 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon ...@@ -8942,7 +8942,7 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i; uint16_t i;
mavlink_camera_capture_status_t packet_in = { mavlink_camera_capture_status_t packet_in = {
963497464,45.0,963497880,101.0,53,120 963497464,45.0,963497880,101.0,53,120,963498400
}; };
mavlink_camera_capture_status_t packet1, packet2; mavlink_camera_capture_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1)); memset(&packet1, 0, sizeof(packet1));
...@@ -8952,6 +8952,7 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon ...@@ -8952,6 +8952,7 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon
packet1.available_capacity = packet_in.available_capacity; packet1.available_capacity = packet_in.available_capacity;
packet1.image_status = packet_in.image_status; packet1.image_status = packet_in.image_status;
packet1.video_status = packet_in.video_status; packet1.video_status = packet_in.video_status;
packet1.image_count = packet_in.image_count;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
...@@ -8966,12 +8967,12 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon ...@@ -8966,12 +8967,12 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_camera_capture_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity ); mavlink_msg_camera_capture_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity , packet1.image_count );
mavlink_msg_camera_capture_status_decode(&msg, &packet2); mavlink_msg_camera_capture_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity ); mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity , packet1.image_count );
mavlink_msg_camera_capture_status_decode(&msg, &packet2); mavlink_msg_camera_capture_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
...@@ -8984,7 +8985,7 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon ...@@ -8984,7 +8985,7 @@ static void mavlink_test_camera_capture_status(uint8_t system_id, uint8_t compon
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_camera_capture_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity ); mavlink_msg_camera_capture_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity , packet1.image_count );
mavlink_msg_camera_capture_status_decode(last_msg, &packet2); mavlink_msg_camera_capture_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
......
This diff is collapsed.
...@@ -2142,7 +2142,8 @@ ...@@ -2142,7 +2142,8 @@
<description>Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage.</description> <description>Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage.</description>
<param index="1" label="Storage ID" minValue="0" increment="1">Storage ID (1 for first, 2 for second, etc.)</param> <param index="1" label="Storage ID" minValue="0" increment="1">Storage ID (1 for first, 2 for second, etc.)</param>
<param index="2" label="Format" minValue="0" maxValue="1" increment="1">0: No action 1: Format storage</param> <param index="2" label="Format" minValue="0" maxValue="1" increment="1">0: No action 1: Format storage</param>
<param index="3">Reserved (all remaining params)</param> <param index="3" label="Reset Image Count" minValue="0" maxValue="1" increment="1">0: No action 1: Reset Image Count</param>
<param index="4">Reserved (all remaining params)</param>
</entry> </entry>
<entry value="527" name="MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS" hasLocation="false" isDestination="false"> <entry value="527" name="MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS" hasLocation="false" isDestination="false">
<deprecated since="2019-08" replaced_by="MAV_CMD_REQUEST_MESSAGE"/> <deprecated since="2019-08" replaced_by="MAV_CMD_REQUEST_MESSAGE"/>
...@@ -6133,6 +6134,8 @@ ...@@ -6133,6 +6134,8 @@
<field type="float" name="image_interval" units="s">Image capture interval</field> <field type="float" name="image_interval" units="s">Image capture interval</field>
<field type="uint32_t" name="recording_time_ms" units="ms">Time since recording started</field> <field type="uint32_t" name="recording_time_ms" units="ms">Time since recording started</field>
<field type="float" name="available_capacity" units="MiB">Available storage capacity.</field> <field type="float" name="available_capacity" units="MiB">Available storage capacity.</field>
<extensions/>
<field type="int32_t" name="image_count">Total number of images.</field>
</message> </message>
<message id="263" name="CAMERA_IMAGE_CAPTURED"> <message id="263" name="CAMERA_IMAGE_CAPTURED">
<description>Information about a captured image. This is emitted every time a message is captured. It may be re-requested using MAV_CMD_REQUEST_MESSAGE, using param2 to indicate the sequence number for the missing image.</description> <description>Information about a captured image. This is emitted every time a message is captured. It may be re-requested using MAV_CMD_REQUEST_MESSAGE, using param2 to indicate the sequence number for the missing image.</description>
...@@ -6144,7 +6147,7 @@ ...@@ -6144,7 +6147,7 @@
<field type="int32_t" name="alt" units="mm">Altitude (MSL) where image was taken</field> <field type="int32_t" name="alt" units="mm">Altitude (MSL) where image was taken</field>
<field type="int32_t" name="relative_alt" units="mm">Altitude above ground</field> <field type="int32_t" name="relative_alt" units="mm">Altitude above ground</field>
<field type="float[4]" name="q">Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)</field> <field type="float[4]" name="q">Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)</field>
<field type="int32_t" name="image_index">Zero based index of this image (image count since armed -1)</field> <field type="int32_t" name="image_index">Zero based index of this image (image count -1)</field>
<field type="int8_t" name="capture_result">Boolean indicating success (1) or failure (0) while capturing this image.</field> <field type="int8_t" name="capture_result">Boolean indicating success (1) or failure (0) while capturing this image.</field>
<field type="char[205]" name="file_url">URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.</field> <field type="char[205]" name="file_url">URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.</field>
</message> </message>
......
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment