# GSDK

## GREMSY SDK INTEGRATION GUIDE

### SDK Documentation Home

\
This document helps you get started with the various aspects of building an SDKapplication and describes the protocol that can be used by software to control Gremsy’sgimbal.&#x20;

The gimbal can be controlled using serial via the **COM2** connector.\
Besides, Gremsy gimbal also supports **MAVProxy** with command gimbal point and&#x20;**MAVSDK** to control the gimbal and autopilot system.

<a href="https://ardupilot.org/mavproxy/docs/modules/gimbal.html" class="button primary" data-icon="computer-mouse"> MAVProxy</a>

\ <a href="https://mavsdk.mavlink.io/main/en/" class="button primary" data-icon="computer-mouse">MAVSDK</a>

### Coordinate System

#### **Earth Frame**

The Earth frames are aircraft-location dependent; the frames are defined tangent to the lines of geographical coordinates. The convention used in the SDK is Local North, East, Down (NED) coordinates. Three perpendicular axes are defined such that the origin is the center of mass, the X-axis is pointing North, and the Y-axis is pointing East.&#x20;

Using the coordinate right-hand rule, the Z-axis is pointing down.

#### Body Frame

The body frame is in the Earth frame rotated so that

* The **X-axis** is pointing forward to the aircraft heading.&#x20;
* The Y-axis is pointing to the right.
* &#x20;and the Z-axis is pointing down.

Gimbal rotation is also described in these frames with Euler Roll, Pitch, and Yaw angles\
rotating around X, Y, and Z axes.

<figure><img src="https://1344889525-files.gitbook.io/~/files/v0/b/gitbook-x-prod.appspot.com/o/spaces%2FvsZHt8KiygBPqGQGbdBQ%2Fuploads%2FptEuwUb25Ou3ykuZpjge%2Fimage.png?alt=media&#x26;token=86e9ea62-24bb-4b67-b218-67b37ace6cb2" alt=""><figcaption></figcaption></figure>

### Working Modes

The gimbal has several work modes that define how the gimbal follows aircraft&#x20;movement and how many axes are available for control.

* **Follow Mode:** Yaw will follow the aircraft heading.
* **Lock Mode:** The gimbal can move independently from the aircraft.

### Moving the Gimbal

The gimbal can be controlled in two input modes:

* Angle Mode: Move to a target attitude
* Speed Mode: Move at a target rate for the individual axis.

When using Angle Mode, the gimbal moves to the target attitude in the Earth frame if operating in Lock mode. Otherwise, the gimbal moves to the target attitude in the body frame if operating in Follow mode.\
When using Speed Mode, the gimbal moves at the absolute rate in the Earth frame.

### General Protocol Overview

The API is implemented based on the MAVLink protocol. Mavlink provides an open data format for interaction as well as a suite of tools to assist the programmer in developing and testing the interface.\
Gimbal uses Mavlink v2.0 message and communicates with other components at **115200** baudrate and 8N1.

### Enable SDK API

#### **Gimbal Data Tranmissions over MAVLink**

* Gimbal sends status data through MAVLink messages. Other components can configure the gimbal to transmit data at the desired rate via MAVLink commands.
* The SDK supports reading data and configuring the gimbal with open APIs.

<figure><img src="https://1344889525-files.gitbook.io/~/files/v0/b/gitbook-x-prod.appspot.com/o/spaces%2FvsZHt8KiygBPqGQGbdBQ%2Fuploads%2FpfjUE5Ff4hoVFVz3v4um%2Fimage.png?alt=media&#x26;token=921b4986-fc8a-4fe6-88d5-73d72d5e57e8" alt="" width="563"><figcaption></figcaption></figure>

**HEARTBEAT (Message ID: #0)**&#x20;

The Gimbal sends HEARTBEAT messages at approximately 1Hz. It sends through COM2 and COM4 on the QR after receiving any HEARTBEAT messages from other components. Take advantage of this message to check the connection between your devices and the gimbal.&#x20;

**SYS\_STATUS (Message ID: #1)**&#x20;

The gimbal pushes status information with SYS\_STATUS messages at approximately 1Hz. Status information includes the working modes, sensor states, and motor states.&#x20;

See `Gimbal_Interface::gimbal_status_t` structure for more details.&#x20;

**RAW\_IMU (Message ID: #27)**&#x20;

The gimbal provides raw imu data for applications that want to inspect data and develop algorithms.&#x20;

Acceleration (raw): range 4g = 8192.&#x20;

Gyro(raw): range 1000dps = 32768.

| Field      | Type      | Description                                                                                                 | Gimbal Implementation |
| ---------- | --------- | ----------------------------------------------------------------------------------------------------------- | --------------------- |
| time\_usec | uint64\_t | Timestamp (us)                                                                                              | Same as official      |
| xacc       | int16\_t  | <p>X acceleration (raw(LSB))<br>Range: ±4 g<br>8192 LBS/g <br>(1 g = 8192)</p>                              | Same as official      |
| yacc       | int16\_t  | <p>Y acceleration (raw(LSB))<br>Range: ±4 g<br>8192 LBS/g <br>(1 g = 8192)</p>                              | Same as official      |
| zacc       | int16\_t  | <p>Z acceleration (raw(LSB))<br>Range: ±4 g<br>8192 LBS/g <br>(1 g = 8192)</p>                              | Same as official      |
| xgyro      | int16\_t  | <p>Angular speed around the X-axis<br>(raw(LSB))<br>Range: ±1000 (°/s)<br>32.8 LSB (°/s)<br>1(°/s)=32.8</p> | Same as official      |
| ygyro      | int16\_t  | <p>Angular speed around the Y-axis<br>(raw(LSB))<br>Range: ±1000 (°/s)<br>32.8 LSB (°/s)<br>1(°/s)=32.8</p> | Same as official      |
| zgyro      | int16\_t  | <p>Angular speed around the Z-axis<br>(raw(LSB))<br>Range: ±1000 (°/s)<br>32.8 LSB (°/s)<br>1(°/s)=32.8</p> | Same as official      |
| xmag       | int16\_t  | X Magnetic field                                                                                            | Ignored               |
| ymag       | int16\_t  | Y Magnetic field                                                                                            | Ignored               |
| zmag       | int16\_t  | Z Magnetic field                                                                                            | Ignored               |

**MOUNT\_STATUS (Message ID: #158)**

This message provides raw encoder values or encoder angle values of the gimbal.The encoder resolution: 2<sup>16</sup> bits.

| Field Name        | Type     | Description  | Gimbal Implementation |
| ----------------- | -------- | ------------ | --------------------- |
| pointing\_a       | int32\_t | Pitch (cdeg) | Tilt encoder value    |
| pointing\_b       | int32\_t | Roll (cdeg)  | Roll encoder value    |
| pointing\_c       | int32\_t | Yaw (cdeg)   | Pan encoder value     |
| target\_system    | uint8\_t | System ID    | Target system ID      |
| target\_component | uint8\_t | Component ID | Target component ID   |

**MOUNT\_ORIENTATION (Message ID: #265)**\
This message contains information about gimbal attitude. Use this message as feedbackwhen controlling the gimbal.

| Field Name        | Type     | Description                    | Gimbal Implementation |
| ----------------- | -------- | ------------------------------ | --------------------- |
| time\_boot\_ms    | int32\_t | Timestamp (ms)                 | Same as official      |
| roll              | float    | Roll in the Earth frame (deg)  | Same as official      |
| pitch             | float    | Pitch in the Earth frame (deg) | Same as official      |
| yaw               | float    | Yaw in the Body frame (deg)    | Same as official      |
| yaw\_absolute\*\* | float    | Yaw in the Earth frame         | Same as official      |

**GIMBAL\_DEVICE\_INFORMATION**\
This message contains gimbal information.

| Field              | Type      | Description                       | Gimbal Implementation |
| ------------------ | --------- | --------------------------------- | --------------------- |
| time\_boot\_ms     | uint32\_t | Timestamp (ms)                    | Same as official      |
| vendor\_name       | char\[32] | Vendor’s name                     | Same as official      |
| model\_name        | char\[32] | Model’s name                      | Same as official      |
| custom\_name       | char\[32] | A custom name is given by theuser | Same as official      |
| firmware\_version  | uint32\_t | Firmware version                  | Same as official      |
| hardware\_version  | uint32\_t | Hardwar version                   | Ignored               |
| uid                | uint64\_t | Hardware uid                      | Ignored               |
| cap\_flags         | uint16\_t | Capability flags                  | Same as official      |
| custom\_cap\_flags | uint16\_t | Specific capability flags         | Ignored               |
| roll\_min          | float     | Minimum hardware roll angle       | Same as official      |
| roll\_max          | float     | Maximum hardware roll angle       | Same as official      |
| pitch\_min         | float     | Minimum hardware pitch angle      | Same as official      |
| pitch\_max         | float     | Maximum hardware pitch angle      | Same as official      |
| yaw\_min           | float     | Minimum hardware yaw angle        | Same as official      |
| yaw\_max           | float     | Maximum hardware yaw angle        | Same as official      |

**GIMBAL\_DEVICE\_ATTITUDE\_STATUS**

The gimbal broadcast this message to report status.

| Field                | Type      | Description                            | Gimbal Implementation |
| -------------------- | --------- | -------------------------------------- | --------------------- |
| target\_system       | uint8\_t  | System ID                              | Same as official      |
| target\_component    | uint8\_t  | Component ID                           | Same as official      |
| time\_boot\_ms       | uint32\_t | Timestamp (ms)                         | Same as official      |
| flags                | uint16\_t | Gimbal flags                           | Same as official      |
| q                    | float\[4] | Gimbal attitude                        | Same as official      |
| angular\_velocity\_x | float     | X component of angularvelocity (rad/s) | Same as official      |
| angular\_velocity\_y | float     | Y component of angularvelocity (rad/s) | Same as official      |
| angular\_velocity\_z | float     | Z component of angular velocity(rad/s) | Same as official      |
| failure\_flags       | uint32\_t | Failure flags                          | Same as official      |

#### **Gimbal Control Messages**

**Common Messages**

Common messages are those used for gimbal control and are independent of theMAVLink Gimbal Protocol version.

**COMMAND\_LONG (Message ID: #76)**

| Field             | Type      | Description            |
| ----------------- | --------- | ---------------------- |
| target\_system    | uint8\_t  | Gimbal System ID       |
| target\_component | uint8\_t  | Gimbal Component ID    |
| command           | uint16\_t | Command ID             |
| confirmation      | uint8\_t  | 0                      |
| param1            | float     | Parameter 1. Default 0 |
| param2            | float     | Parameter 2. Default 0 |
| param3            | float     | Parameter 3. Default 0 |
| param4            | float     | Parameter 4. Default 0 |
| param5            | float     | Parameter 5. Default 0 |
| param6            | float     | Parameter 6. Default 0 |
| param7            | float     | Parameter 7. Default 0 |

command: **MAV\_CMD\_USER\_1**

This command is used to turn the gimbal motor on or off

| Param (: Label) | Description | Values        |
| --------------- | ----------- | ------------- |
| 7:              | ON/OFF      | 0: OFF, 1: ON |

command: **MAV\_CMD\_DO\_MOUNT\_CONFIGURE**

This command is used to configure gimbal mount mode. Detailed implementation is in SDK.

| Param (: Label) | Description          | Values                        |
| --------------- | -------------------- | ----------------------------- |
| 1: Mode         | Mount operation mode | See MAV\_MOUNT\_MODE and APIs |

command: **MAV\_CMD\_PREFLIGHT\_REBOOT\_SHUTDOWN**

This command is used to reboot the gimbal.

| Param (: Label) | Description                  | Values |
| --------------- | ---------------------------- | ------ |
| 4: Flag         | Flag to check reboot command | 1      |

command: **MAV\_CMD\_REQUEST\_MESSAGE**

This command is used to request gimbal emit a single instance of a specified message.

| Param (: Label) | Description                                     | Values     |
| --------------- | ----------------------------------------------- | ---------- |
| 1: Message ID   | The MAVLink message ID of the requested message | Message ID |

command: **MAV\_CMD\_SET\_MESSAGE\_INTERVAL**

This command is used to request and set the interval between messages for a particular MAVLink message ID.

| Param (: Label) | Description                                                                            | Values        |
| --------------- | -------------------------------------------------------------------------------------- | ------------- |
| 1: Message ID   | The MAVLink message ID of the requested message                                        | Message ID    |
| 2: Interval     | The interval between 2 messages. Set to -1 to disableand 0 to request the default rate | Interval (us) |

**COMMAND\_ACK (Message ID: #77)**

<figure><img src="https://1344889525-files.gitbook.io/~/files/v0/b/gitbook-x-prod.appspot.com/o/spaces%2FvsZHt8KiygBPqGQGbdBQ%2Fuploads%2FNkSCY1DjTyJ9HYbHAOOd%2Fimage.png?alt=media&#x26;token=90aa411a-b810-43c3-af88-a06835beeb78" alt=""><figcaption></figcaption></figure>

The MAVLink command protocol allows for guaranteed delivery of MAVLink commands. The gimbal responds to commands from other components with COMMAND\_ACK. Additionally, the gimbal waits for a COMMAND\_ACK response from other components when sending commands.

| Field                  | Type      | Description         |
| ---------------------- | --------- | ------------------- |
| commad                 | uint16\_t | Command ID          |
| result                 | uint8\_t  | Result of command.  |
| progress \*\*          | uint8\_t  | Ignored             |
| result\_param2 \*\*    | int32\_t  | Ignored             |
| target\_system \*\*    | uint8\_t  | Target System ID    |
| target\_component \*\* | uint8\_t  | Target Component ID |

### MAVLink Gimbal Protocol V1

The messages below are specific messages implemented for gimbal control in the MAVLink Gimbal Protocol V1.

COMMAND\_LONG (Message ID: #76)

**command: MAV\_CMD\_DO\_MOUNT\_CONTROL**

This command is used to control the gimbal to move to the target attitude or at the target speed.

| Param (: Label) | Description         | Values                                   |
| --------------- | ------------------- | ---------------------------------------- |
| 1: Pitch        | Pitch control value | Depends on the input mode (deg or deg/s) |
| 2: Roll         | Roll control value  | Depends on the input mode (deg or deg/s) |
| 3: Yaw          | Yaw control value   | Depends on the input mode (deg or deg/s) |
| 6: Input mode   | Input mode          | See Gimbal\_Protocol::input\_mode\_t     |
| 7: Mount mode   | Mount mode          | MAV\_MOUNT\_MODE\_MAVLINK\_TARGETTING    |

**command: MAV\_CMD\_USER\_2**

This command is used to change the gimbal control mode Lock/Follow.

| Param (: Label) | Description  | Values                                       |
| --------------- | ------------ | -------------------------------------------- |
| 6: Reset mode   | Reset mode   | See Gimbal\_Protocol::gimbal\_reset\_mode\_t |
| 7: Control mode | Control mode | See Gimbal\_Protocol::control\_mode\_t       |

### MAVLink Gimbal Protocol V2

**GIMBAL\_DEVICE\_SET\_ATTITUDE**

This message is used to control the gimbal device.

| Field                | Type      | Description                             |
| -------------------- | --------- | --------------------------------------- |
| target\_system       | uint8\_t  | Gimbal System ID                        |
| target\_component    | uint8\_t  | Gimbal Component ID                     |
| flags                | uint16\_t | Low level gimbal flags.                 |
| q                    | float\[4] | Target attitude in quaternion form      |
| angular\_velocity\_x | float     | X component of angular velocity (rad/s) |
| angular\_velocity\_y | float     | Y component of angular velocity (rad/s) |
| angular\_velocity\_z | float     | Z component of angular velocity (rad/s) |

**AUTOPILOT\_STATE\_FOR\_GIMBAL\_DEVICE**

This message contains the autopilot state for the gimbal device.

| Field                   | Type      | Description                           |
| ----------------------- | --------- | ------------------------------------- |
| target\_system          | uint8\_t  | Gimbal System ID                      |
| target\_component       | uint8\_t  | Gimbal Component ID                   |
| time\_boot\_us          | uint64\_t | Timestamp (us)                        |
| q                       | float\[4] | Autopilot attitude in quaternion form |
| q\_estimated\_delay\_us | uint32\_t | Estimated delay of the attitude data  |

| v\_x                                | float     | X Speed in NED (m/s)                                |
| ----------------------------------- | --------- | --------------------------------------------------- |
| v\_y                                | float     | Y Speed in NED (m/s)                                |
| v\_z                                | float     | Z Speed in NED (m/s)                                |
| v\_estimated\_delay\_us             | uint32\_t | Estimated delay of the speed data                   |
| feed\_forward\_angular\_velocity\_z | float     | Feedforward Z component of angular velocity (rad/s) |
| estimator\_status                   | uint16\_t | Bitmap indicating which estimator outputs are valid |
| landed\_state                       | uint8\_t  | The landed state                                    |

#### **APIs Reference**

Public Types

| Type                                                | Description                           |
| --------------------------------------------------- | ------------------------------------- |
| struct Gimbal\_Interface::time\_stamps\_t           | Gimbal messages timestamps            |
| enum Gimbal\_Interface::control\_direction\_t       | Gimbal axis control direction         |
| enum Gimbal\_Interface::control\_motor\_t           | Gimbal motor mode ON/OFF              |
| enum Gimbal\_Interface::operation\_state\_t         | Gimbal operation state                |
| struct Gimbal\_Interface::fw\_version\_t            | Gimbal firmware version               |
| struct Gimbal\_Interface::gimbal\_status\_t         | Gimbal status                         |
| struct Gimbal\_Interface::gimbal\_config\_axis\_t   | Gimbal axis motion parameters         |
| struct Gimbal\_Interface::gimbal\_motor\_control\_t | Gimbal axis stiffness parameters      |
| enum Gimbal\_Interface::MAVLINK\_PROTO              | MAVLink gimbal protocol version       |
| struct Gimbal\_Interface::limit\_angle\_t           | Gimbal axis software limit            |
| struct Gimbal\_Interface::imu\_t                    | Gimbal imu data type                  |
| enum Gimbal\_Protocol::result\_t                    | Enum described function return status |
| enum Gimbal\_Protocol::control\_mode\_t             | Gimbal control mode                   |
| enum Gimbal\_Protocol::gimbal\_reset\_mode\_t       | Gimbal reset mode                     |
| enum Gimbal\_Interface::rc\_type\_t                 | Gimbal remote controller type         |

**Public Member Functions**

| Type                                                                                                | Name                                                                                            | Description                                                                                             |
| --------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------- |
| Gimbal\_Interface(Serial\_Port\*serial\_port, uint8\_t sysid, uint8\_tcompid, MAVLINK\_PROTO proto) | Constructor. Creates a gimbalinterface for a specific systemand MAVLink Gimbal Protocolversion. |                                                                                                         |
| \~Gimbal\_Interface()                                                                               | Destructor.                                                                                     |                                                                                                         |
| void                                                                                                | start()                                                                                         | Starts the gimbal interface.                                                                            |
| void                                                                                                | stop()                                                                                          | Stops the gimbal interface.                                                                             |
| void                                                                                                | start\_read\_thread()                                                                           | Internal use only.                                                                                      |
| void                                                                                                | start\_write\_thread()                                                                          | Internal use only.                                                                                      |
| void                                                                                                | handle\_quit()                                                                                  | Quit handler.                                                                                           |
| bool                                                                                                | get\_flag\_exit()                                                                               | Checks if the interface hasstopped.                                                                     |
| bool                                                                                                | get\_connection()                                                                               | Check if the interface hasconnected to the gimbal device.                                               |
| bool                                                                                                | present()                                                                                       | Check if the gimbal is ready tocontrol.                                                                 |
| Gimbal\_Protocol::result\_t                                                                         | set\_gimbal\_reboot()                                                                           | Reboots gimbal.                                                                                         |
| Gimbal\_Protocol::result\_t                                                                         | set\_gimbal\_rc\_input\_sync()                                                                  | Sets the gimbal to RC Inputmode, will return when thecommand is responded to. Thisfunction is blocking. |
| Gimbal\_Protocol::result\_t                                                                         | set\_gimbal\_motor(control\_motor\_t type)                                                      | Sets the gimbal motor ON/OFF.                                                                           |
| Gimbal\_Protocol::control\_mode\_t                                                                  | get\_gimbal\_mode()                                                                             | Gets the gimbal control mode.                                                                           |

| Gimbal\_Protocol::result\_t          | set\_gimbal\_reset\_mode(gimbal\_reset\_mode\_t reset\_mode)          | Resets the gimbal with a specificmode.                                                                       |
| ------------------------------------ | --------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------ |
| Gimbal\_Protocol::result\_t          | set\_gimbal\_lock\_mode\_sync()                                       | Sets the gimbal to Lock mode,will return when the command isresponded to. This function isblocking.          |
| Gimbal\_Protocol::result\_t          | set\_gimbal\_follow\_mode\_sync()                                     | Sets the gimbal to Follow mode,will return when the command isresponded to. This function isblocking.        |
| Gimbal\_Protocol::result\_t          | set\_gimbal\_rotation\_sync(floatpitch, float roll, float yaw)        | Rotates the gimbal to targetattitude, will return when thecommand is responded to. Thisfunction is blocking. |
| Gimbal\_Protocol::result\_t          | set\_gimbal\_rotation\_rate\_sync(float pitch, float roll, float yaw) | Rotates the gimbal at target rate,and will return when thecommand is responded to. Thisfunction is blocking. |
| Gimbal\_Interface::gimbal\_status\_t | get\_gimbal\_status()                                                 | Gets the gimbal status.                                                                                      |
| Gimbal\_Interface::imu\_t            | get\_gimbal\_raw\_imu()                                               | Gets the gimbal raw imu data.                                                                                |
| attitude\<float>                     | get\_gimbal\_attitude()                                               | Gets the gimbal attitude.                                                                                    |
| attitude\<int16\_t>                  | get\_gimbal\_encoder()                                                | Gets the gimbal encoder value,depending on the encoder typesend.                                             |
| Gimbal\_Interface::timestamps\_t     | get\_gimbal\_timestamps()                                             | Gets the gimbal timestamps.                                                                                  |
| Gimbal\_Interface::fw\_version\_t    | get\_gimbal\_version()                                                | Gets the gimbal firmwareversion.                                                                             |

| Gimbal\_Protocol::result\_t                | set\_gimbal\_config\_tilt\_axis(constgimbal\_config\_axis\_t \&config)                                                                                                                                       | Configures the gimbal tilt axismotion parameters. |
| ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------- |
| Gimbal\_Interface::gimbal\_config\_axis\_t | get\_gimbal\_config\_tilt\_axis()                                                                                                                                                                            | Gets the gimbal tilt axis motionparameters        |
| Gimbal\_Protocol::result\_t                | set\_gimbal\_config\_roll\_axis(constgimbal\_config\_axis\_t \&config)                                                                                                                                       | Configures the gimbal roll axismotion parameters. |
| Gimbal\_Interface::gimbal\_config\_axis\_t | get\_gimbal\_config\_roll\_axis()                                                                                                                                                                            | Gets the gimbal roll axis motionparameters        |
| Gimbal\_Protocol::result\_t                | set\_gimbal\_config\_pan\_axis(constgimbal\_config\_axis\_t \&config)                                                                                                                                        | Configures the gimbal pan axismotion parameters.  |
| Gimbal\_Interface::gimbal\_config\_axis\_t | get\_gimbal\_config\_pan\_axis()                                                                                                                                                                             | Gets the gimbal pans axismotion parameters        |
| Gimbal\_Protocol::result\_t                | get\_gimbal\_motor\_control(gimbal\_motor\_control\_t \&tilt,gimbal\_motor\_control\_t \&roll,gimbal\_motor\_control\_t \&pan,uint8\_t \&gyro\_filter, uint8\_t\&output\_filter, uint8\_t \&gain)            | Get the gimbal motorconfiguration.                |
| Gimbal\_Protocol::result\_t                | set\_gimbal\_motor\_control(constgimbal\_motor\_control\_t \&tilt, constgimbal\_motor\_control\_t \&roll, constgimbal\_motor\_control\_t \&pan,uint8\_t gyro\_filter, uint8\_toutput\_filter, uint8\_t gain) | Configures the gimbal motorparameters.            |
| Gimbal\_Protocol::result\_t                | set\_msg\_encoder\_rate(uint8\_t rate)                                                                                                                                                                       | Sets the gimbal encodermessages rate.s            |
| Gimbal\_Protocol::result\_t                | set\_msg\_mnt\_orient\_rate(uint8\_trate)                                                                                                                                                                    | Sets the gimbal mountorientation messages rate.   |
| Gimbal\_Protocol::result\_t                | set\_msg\_attitude\_status\_rate(uint8\_trate)                                                                                                                                                               | Sets the gimbal attitude statusmessages rate.     |

| Gimbal\_Protocol::result\_t        | set\_msg\_raw\_imu\_rate(uint8\_t rate)                                  | Sets the gimbal raw imumessages rate.                    |
| ---------------------------------- | ------------------------------------------------------------------------ | -------------------------------------------------------- |
| Gimbal\_Protocol::result\_t        | set\_gimbal\_encoder\_type\_send(booltype)                               | Sets the gimbal encoder typesend.                        |
| Gimbal\_Protocol::result\_t        | request\_gimbal\_device\_info()                                          | Requests the gimbal deviceinformation.                   |
| bool                               | get\_gimbal\_encoder\_type\_send()                                       | Gets the gimbal encoder typesend.                        |
| Gimbal\_Protocol::result\_t        | set\_gimbal\_combine\_attitude(boolflag)                                 | Sets the gimbal enabling reducedyaw drifting.            |
| Gimbal\_Protocol::result\_t        | <p>set\_limit\_angle\_pitch<br>(constlimit\_angle\_t \&limit\_angle)</p> | <p>Sets the gimbal pitch axis limit.<br>Unit: Degree</p> |
| Gimbal\_Interface::limit\_angle\_t | get\_limit\_angle\_pitch()                                               | Gets the gimbal pitch axis limit.                        |
| Gimbal\_Protocol::result\_t        | set\_limit\_angle\_yaw(constlimit\_angle\_t \&limit\_angle)              | <p>Sets the gimbal yaw axis limit.<br>Unit: Degree</p>   |
| Gimbal\_Interface::limit\_angle\_t | get\_limit\_angle\_yaw()                                                 | Gets the gimbal yaw axis limit.                          |
| Gimbal\_Protocol::result\_t        | set\_limit\_angle\_roll(constlimit\_angle\_t \&limit\_angle)             | <p>Sets the gimbal roll axis limit.<br>Unit: Degree</p>  |
| Gimbal\_Interface::limit\_angle\_t | get\_limit\_angle\_roll()                                                | Gets the gimbal roll axis limit.                         |
| Gimbal\_Protocoll::result\_t       | set\_rc\_type(rc\_type\_t type)                                          | Set the external RC type for thegimbal.                  |

<br>

<br>

\ <br>

<br>

\
\ <br>
