# PAYLOADSDK

## Table of contents <a href="#bkmrk-table-of-contents" id="bkmrk-table-of-contents"></a>

* Table of contents
* Version history
* MAVLINK Messages

**Set Camera Commands**

1. [Set camera running mode](#set-camera-running-mode)
2. [Set camera record source](#set-camera-record-source)
3. [Set camera view source](#set-camera-view-source)
4. [Set EO camera zoom mode](#set-eo-camera-zoom-mode)
5. [Set EO camera zoom - Super Resolution](#set-eo-camera-zoom-super-resolution)
6. [Set EO camera index zoom - Combine](#set-eo-camera-index-zoom-combine)
7. [Set camera zoom type](#set-camera-zoom-type)
8. [Set camera focus type](#set-camera-focus-type)
9. [Set camera IR palette](#set-camera-ir-palette)
10. [Set payload camera start capture image](#set-payload-camera-start-capture-image)
11. [Set payload camera stop capture image](#set-payload-camera-stop-capture-image)
12. [Set payload camera start record video](#set-payload-camera-start-record-video)
13. [Set payload camera stop record video](#set-payload-camera-stop-record-video)
14. [Set camera video flip](#set-camera-video-flip)
15. [Set camera video defog](#set-camera-video-defog)
16. [Set camera video defog level](#set-camera-video-defog-level)
17. [Set camera video auto exposure](#set-camera-video-auto-exposure)
18. [Set camera video shutter speed](#set-camera-video-shutter-speed)
19. [Set camera video aperture value](#set-camera-video-aperture-value)
20. [Set camera video bright value](#set-camera-video-bright-value)
21. [Set camera video white balance](#set-camera-video-white-balance)

**Set Gimbal Commands**

1. [Set gimbal mode](#set-gimbal-mode)
2. [Set gimbal RC mode](#set-gimbal-rc-mode)
3. [Set gimbal move to angle](#set-gimbal-move-to-angle)
4. [Set gimbal move by speed](#set-gimbal-move-by-speed)

**Get Payload Information**

1. [Get payload camera information](#get-payload-camera-information)
2. [Get payload camera streaming information](#get-payload-camera-streaming-information)
3. [Get payload storage](#get-payload-storage)
4. [Get payload capture status](#get-payload-capture-status)
5. [Get payload camera mode](#get-payload-camera-mode)

## Version history <a href="#bkmrk-version-history" id="bkmrk-version-history"></a>

| Version | Publish date | Description                                                                                                                                                                                                                                                                                |
| ------- | ------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| 1.0.0   | 06 Jan 2023  | <p>Add example to do Connect payload<br>Add example to do Load payload settings<br>Add example to do Set payload settings<br>Add example to do Image capture with the payload<br>Add example to do Video record with the payload<br>Add example to do Get video streaming from payload</p> |
| 1.0.1   | 25 May 2023  | <p>Included Gremsy gSDK to communicate and control gimbal<br>Add examples to move gimbal in Angle mode and Angular rate mode using Mavlink Gimbal Protocol v2</p>                                                                                                                          |
| v1.1.0  | 30 July 2024 | <p>Add some examples<br>Get LRF status for VIO<br>Payload define</p>                                                                                                                                                                                                                       |
| v2.0.0  | 16 Aug 2024  | <p>Replace gSDK by MAVLINK interface<br>Provide MAVLINK command list<br>Publish resource</p>                                                                                                                                                                                               |

## MAVLINK Messages <a href="#bkmrk-mavlink-messages" id="bkmrk-mavlink-messages"></a>

| Encode a command\_long struct | Values | Description                      |
| ----------------------------- | ------ | -------------------------------- |
| target\_system                | 1      |                                  |
| target\_component             | 191    | MAV\_COMP\_ID\_ONBOARD\_COMPUTER |
| chan                          | 0      | MAVLink channel                  |

### **Set camera running mode**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                            | Description                                |
| ----------------- | --------- | --------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                 | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)      | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_SET\_CAMERA\_MODE (530) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                 |                                            |
| param2            | float     | <p>0<br>1</p>                     | <p>Photo mode<br>Video mode</p>            |

### **Set camera record source**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                          | Description                                                |
| ----------------- | ---------- | ------------------------------- | ---------------------------------------------------------- |
| target\_system    | uint8\_t   | 1                               | System ID                                                  |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)    | MAVLINK Camera Component ID on Web setting                 |
| param\_id         | char\[16]  | "C\_V\_REC"                     |                                                            |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"5"</p> | <p>Record both<br>Record EO<br>Record IR<br>Record OSD</p> |
| param\_type       | uint8\_t   | UINT32                          | MAV\_PARAM\_EXT\_TYPE                                      |

### **Set camera view source**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                 | Description                                         |
| ----------------- | ---------- | -------------------------------------- | --------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                      | System ID                                           |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)           | MAVLINK Camera Component ID on Web setting          |
| param\_id         | char\[16]  | "C\_SOURCE"                            |                                                     |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"<br>"4"</p> | <p>EO/IR<br>Only EO<br>Only IR<br>IR/EO<br>Sync</p> |
| param\_type       | uint8\_t   | UINT32                                 | MAV\_PARAM\_EXT\_TYPE                               |

### **Set EO camera zoom mode**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                       | Description                                |
| ----------------- | ---------- | ---------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t   | 1                            | System ID                                  |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting |
| param\_id         | char\[16]  | "C\_V\_ZM\_MODE"             |                                            |
| param\_value      | char\[128] | <p>"0"<br>"2"</p>            | <p>Combine<br>Super Resolution</p>         |
| param\_type       | uint8\_t   | UINT32                       | MAV\_PARAM\_EXT\_TYPE                      |

### **Set EO camera zoom - Super Resolution**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                                                                                                    | Description                                                                                                    |
| ----------------- | ---------- | ------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                                                                                                         | System ID                                                                                                      |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)                                                                                              | MAVLINK Camera Component ID on Web setting                                                                     |
| param\_id         | char\[16]  | "C\_V\_ZM\_SR\_LV"                                                                                                        |                                                                                                                |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"<br>"4"<br>"5"<br>"6"<br>"7"<br>"8"<br>"9"<br>"10"<br>"11"<br>"12"<br>"13"<br>"14"<br>"15"</p> | <p>1X<br>2X<br>4X<br>6X<br>8X<br>10X<br>12X<br>14X<br>16X<br>18X<br>20X<br>22X<br>24X<br>26X<br>28X<br>30X</p> |
| param\_type       | uint8\_t   | UINT32                                                                                                                    | MAV\_PARAM\_EXT\_TYPE                                                                                          |

### **Set EO camera index zoom - Combine**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                               | Description                                           |
| ----------------- | ---------- | ---------------------------------------------------- | ----------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                                    | System ID                                             |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)                         | MAVLINK Camera Component ID on Web setting            |
| param\_id         | char\[16]  |                                                      | "C\_V\_ZM\_CB\_LV"                                    |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"<br>"4"<br>"5"<br>"6"</p> | <p>1X<br>10X<br>20X<br>40X<br>80X<br>120X<br>240X</p> |
| param\_type       | uint8\_t   | UINT32                                               | MAV\_PARAM\_EXT\_TYPE                                 |

### **Set camera zoom type**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                                                                                                   | Description                                                                                                              |
| ----------------- | --------- | ------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------ |
| target\_system    | uint8\_t  | 1                                                                                                                        | System ID                                                                                                                |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)                                                                                             | MAVLINK Camera Component ID on Web setting                                                                               |
| command           | uint16\_t | MAV\_CMD\_SET\_CAMERA\_ZOOM (531)                                                                                        | MAV\_CMD                                                                                                                 |
| confirmation      | uint8\_t  | 1                                                                                                                        |                                                                                                                          |
| param1            | float     | <p>0<br>1<br>2</p>                                                                                                       | <p>ZOOM\_TYPE\_STEP<br>ZOOM\_TYPE\_CONTINUOUS<br>ZOOM\_TYPE\_RANGE</p>                                                   |
| param2            | float     | <p>-1 for wide, 1 for tele<br>-1 for wide, 1 for tele, 0 to stop zooming<br>A percentage value between 0.0 and 100.0</p> | <p>Zoom one step increment<br>Continuous zoom up/down until stopped<br>Zoom value as proportion of full camera range</p> |

### **Set camera focus type**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                    | Description                                         |
| ----------------- | --------- | ----------------------------------------- | --------------------------------------------------- |
| target\_system    | uint8\_t  | 1                                         | System ID                                           |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)              | MAVLINK Camera Component ID on Web setting          |
| command           | uint16\_t | MAV\_CMD\_SET\_CAMERA\_FOCUS (532)        | MAV\_CMD                                            |
| confirmation      | uint8\_t  | 1                                         |                                                     |
| param1            | float     | <p>1<br>4</p>                             | <p>FOCUS\_TYPE\_CONTINUOUS<br>FOCUS\_TYPE\_AUTO</p> |
| param2            | float     | -1: focusing in, 1: focusing out, 0: stop | Continuous focus up/down until stopped              |

### **Set camera IR palette**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                                                    | Description                                                                                                                                                                                                                                                                                               |
| ----------------- | ---------- | ------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                                                         | System ID                                                                                                                                                                                                                                                                                                 |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)                                              | MAVLINK Camera Component ID on Web setting                                                                                                                                                                                                                                                                |
| param\_id         | char\[16]  | "C\_T\_PALETTE"                                                           |                                                                                                                                                                                                                                                                                                           |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"<br>"4"<br>"5"<br>"6"<br>"7"<br>"8"<br>"9"</p> | <p>F1: WhiteHot ; G1: WhiteHot<br>F1: BlackHot ; G1: Fulgurite<br>F1: Rainbow ; G1: IronRed<br>F1: RainbowHC ; G1: HotIron<br>F1: Ironbow ; G1: Medical<br>F1: Lava ; G1: Arctic<br>F1: Arctic ; G1: Rainbow1<br>F1: Globow ; G1: Rainbow2<br>F1: Gradedfire ; G1: Tint<br>F1: Hottest ; G1: BlackHot</p> |
| param\_type       | uint8\_t   | UINT32                                                                    | MAV\_PARAM\_EXT\_TYPE                                                                                                                                                                                                                                                                                     |

### **Set payload camera start capture image**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                 | Description                                                        |
| ----------------- | --------- | -------------------------------------- | ------------------------------------------------------------------ |
| target\_system    | uint8\_t  | 1                                      | System ID                                                          |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)           | MAVLINK Camera Component ID on Web setting                         |
| command           | uint16\_t | MAV\_CMD\_IMAGE\_START\_CAPTURE (2000) | MAV\_CMD                                                           |
| confirmation      | uint8\_t  | 1                                      |                                                                    |
| param2            | int       | Default, min: 0                        | Desired elapsed time between two consecutive pictures (in seconds) |

### **Set payload camera stop capture image**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                | Description                                |
| ----------------- | --------- | ------------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                     | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)          | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_IMAGE\_STOP\_CAPTURE (2001) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                     |                                            |

### **Set payload camera start record video**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                 | Description                                |
| ----------------- | --------- | -------------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                      | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)           | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_VIDEO\_START\_CAPTURE (2500) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                      |                                            |

### **Set payload camera stop record video**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                       | Description                                |
| ----------------- | --------- | ---------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                            | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD                     | MAV\_CMD\_VIDEO\_STOP\_CAPTURE (2501)      |
| confirmation      | uint8\_t  | 1                            |                                            |

### **Set camera video flip**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                       | Description                                |
| ----------------- | ---------- | ---------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t   | 1                            | System ID                                  |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting |
| param\_id         | char\[16]  | "C\_V\_FLIP"                 |                                            |
| param\_value      | char\[128] | <p>"2"<br>"3"</p>            | <p>On<br>Off</p>                           |
| param\_type       | uint8\_t   | UINT32                       | MAV\_PARAM\_EXT\_TYPE                      |

### **Set camera video defog**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                       | Description                                |
| ----------------- | ---------- | ---------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t   | 1                            | System ID                                  |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting |
| param\_id         | char\[16]  | "C\_V\_DEFOG"                |                                            |
| param\_value      | char\[128] | <p>"0"<br>"1"</p>            | <p>Off<br>On</p>                           |
| param\_type       | uint8\_t   | UINT32                       | MAV\_PARAM\_EXT\_TYPE                      |

### **Set camera video defog level**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                          | Description                                |
| ----------------- | ---------- | ------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t   | 1                               | System ID                                  |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)    | MAVLINK Camera Component ID on Web setting |
| param\_id         | char\[16]  | "C\_V\_DEFOG\_LV"               |                                            |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"</p> | <p>Lowest<br>Low<br>Mid<br>High</p>        |
| param\_type       | uint8\_t   | UINT32                          | MAV\_PARAM\_EXT\_TYPE                      |

### **Set camera video auto exposure**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                    | Description                                        |
| ----------------- | ---------- | ----------------------------------------- | -------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                         | System ID                                          |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)              | MAVLINK Camera Component ID on Web setting         |
| param\_id         | char\[16]  | "C\_V\_AE"                                |                                                    |
| param\_value      | char\[128] | <p>"0"<br>"3"<br>"10"<br>"11"<br>"13"</p> | <p>Auto<br>Manual<br>Shutter<br>Iris<br>Bright</p> |
| param\_type       | uint8\_t   | UINT32                                    | MAV\_PARAM\_EXT\_TYPE                              |

### **Set camera video shutter speed**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                                                              | Description                                                                                   |
| ----------------- | ---------- | ----------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                                                                   | System ID                                                                                     |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)                                                        | MAVLINK Camera Component ID on Web setting                                                    |
| param\_id         | char\[16]  | "C\_V\_SP"                                                                          |                                                                                               |
| param\_value      | char\[128] | <p>"13"<br>"14"<br>"17"<br>"20"<br>"21"<br>"25"<br>"26"<br>"27"<br>"28"<br>"30"</p> | <p>1/10<br>1/20<br>1/50<br>1/100<br>1/125<br>1/500<br>1/725<br>1/1000<br>1/1500<br>1/2000</p> |
| param\_type       | uint8\_t   | UINT32                                                                              | MAV\_PARAM\_EXT\_TYPE                                                                         |

### **Set camera video aperture value**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                       | Description                                    |
| ----------------- | ---------- | ---------------------------- | ---------------------------------------------- |
| target\_system    | uint8\_t   | 1                            | System ID                                      |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting     |
| param\_id         | char\[16]  | "C\_V\_IrP"                  |                                                |
| param\_value      | char\[128] | 0                            | Aperture value can be set from 0 to 25, step 1 |
| param\_type       | uint8\_t   | UINT32                       | MAV\_PARAM\_EXT\_TYPE                          |

### **Set camera video bright value**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                       | Description                                  |
| ----------------- | ---------- | ---------------------------- | -------------------------------------------- |
| target\_system    | uint8\_t   | 1                            | System ID                                    |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting   |
| param\_id         | char\[16]  | "C\_V\_BrP"                  |                                              |
| param\_value      | char\[128] | 0                            | Bright value can be set from 0 to 41, step 1 |
| param\_type       | uint8\_t   | UINT32                       | MAV\_PARAM\_EXT\_TYPE                        |

### **Set camera video white balance**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                        | Description                                                   |
| ----------------- | ---------- | --------------------------------------------- | ------------------------------------------------------------- |
| target\_system    | uint8\_t   | 1                                             | System ID                                                     |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)                  | MAVLINK Camera Component ID on Web setting                    |
| param\_id         | char\[16]  | "C\_V\_WB"                                    |                                                               |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"<br>"4"<br>"5"</p> | <p>Auto<br>Indoor<br>Outdoor<br>One push<br>ATW<br>Manual</p> |
| param\_type       | uint8\_t   | UINT32                                        | MAV\_PARAM\_EXT\_TYPE                                         |

### **Set gimbal mode**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                                 | Description                                      |
| ----------------- | ---------- | -------------------------------------- | ------------------------------------------------ |
| target\_system    | uint8\_t   | 1                                      | System ID                                        |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2)           | MAVLINK Camera Component ID on Web setting       |
| param\_id         | char\[16]  | "GB\_MODE"                             |                                                  |
| param\_value      | char\[128] | <p>"0"<br>"1"<br>"2"<br>"3"<br>"4"</p> | <p>OFF<br>LOCK<br>FOLLOW<br>MAPPING<br>RESET</p> |
| param\_type       | uint8\_t   | UINT32                                 | MAV\_PARAM\_EXT\_TYPE                            |

### **Set gimbal RC mode**

* Message: PARAM\_EXT\_SET (323)

| Field Name        | Type       | Values                       | Description                                |
| ----------------- | ---------- | ---------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t   | 1                            | System ID                                  |
| target\_component | uint8\_t   | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting |
| param\_id         | char\[16]  | "RC\_MODE"                   |                                            |
| param\_value      | char\[128] | <p>"0"<br>"1"</p>            | <p>Gremsy<br>Standard</p>                  |
| param\_type       | uint8\_t   | UINT32                       | MAV\_PARAM\_EXT\_TYPE                      |

### **Set gimbal move to angle**

* Message: GIMBAL\_DEVICE\_SET\_ATTITUDE (284)

| Field Name           | Type      |       | Values                                              | Description                                |
| -------------------- | --------- | ----- | --------------------------------------------------- | ------------------------------------------ |
| target\_system       | uint8\_t  |       | 1                                                   | System ID                                  |
| target\_component    | uint8\_t  |       | 101 (MAV\_COMP\_ID\_CAMERA2)                        | MAVLINK Camera Component ID on Web setting |
| q                    | float\[4] | rad/s | mavlink\_euler\_to\_quaternion(roll, pitch, yaw, q) | Quaternion components, w, x, y, z          |
| angular\_velocity\_x | float     | rad/s | NaN                                                 | X component of angular velocity (Roll)     |
| angular\_velocity\_y | float     | rad/s | NaN                                                 | Y component of angular velocity (Pitch)    |
| angular\_velocity\_z | float     | rad/s | NaN                                                 | Z component of angular velocity (Yaw)      |

### **Set gimbal move by speed**

* Message: GIMBAL\_DEVICE\_SET\_ATTITUDE (284)

| Field Name           | Type      |       | Values                       | Description                                |
| -------------------- | --------- | ----- | ---------------------------- | ------------------------------------------ |
| target\_system       | uint8\_t  |       | 1                            | System ID                                  |
| target\_component    | uint8\_t  |       | 101 (MAV\_COMP\_ID\_CAMERA2) | MAVLINK Camera Component ID on Web setting |
| q                    | float\[4] | rad/s | NaN                          | Quaternion components, w, x, y, z          |
| angular\_velocity\_x | float     | rad/s | Speed roll                   | X component of angular velocity (Roll)     |
| angular\_velocity\_y | float     | rad/s | Speed pitch                  | Y component of angular velocity (Pitch)    |
| angular\_velocity\_z | float     | rad/s | Speed yaw                    | Z component of angular velocity (Yaw)      |

### **Get payload camera information**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                       | Description                                |
| ----------------- | --------- | -------------------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                            | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)                 | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_REQUEST\_CAMERA\_INFORMATION (521) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                            |                                            |

### **Get payload camera streaming information**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                               | Description                                |
| ----------------- | --------- | ---------------------------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                                    | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)                         | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_REQUEST\_VIDEO\_STREAM\_INFORMATION (2504) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                                    |                                            |

### **Get payload storage**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                        | Description                                |
| ----------------- | --------- | --------------------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                             | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)                  | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_REQUEST\_STORAGE\_INFORMATION (525) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                             |                                            |

### **Get payload capture status**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                           | Description                                |
| ----------------- | --------- | ------------------------------------------------ | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                                | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)                     | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_REQUEST\_CAMERA\_CAPTURE\_STATUS (527) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                                |                                            |

### **Get payload camera mode**

* Message: COMMAND\_LONG (76)

| Field Name        | Type      | Values                                    | Description                                |
| ----------------- | --------- | ----------------------------------------- | ------------------------------------------ |
| target\_system    | uint8\_t  | 1                                         | System ID                                  |
| target\_component | uint8\_t  | 101 (MAV\_COMP\_ID\_CAMERA2)              | MAVLINK Camera Component ID on Web setting |
| command           | uint16\_t | MAV\_CMD\_REQUEST\_CAMERA\_SETTINGS (522) | MAV\_CMD                                   |
| confirmation      | uint8\_t  | 1                                         |                                            |
