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.
The gimbal can be controlled using serial via the COM2 connector. Besides, Gremsy gimbal also supports MAVProxy with command gimbal point and MAVSDK to control the gimbal and autopilot system.
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.
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.
The Y-axis is pointing to the right.
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.

Working Modes
The gimbal has several work modes that define how the gimbal follows aircraft 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.

HEARTBEAT (Message ID: #0)
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.
SYS_STATUS (Message ID: #1)
The gimbal pushes status information with SYS_STATUS messages at approximately 1Hz. Status information includes the working modes, sensor states, and motor states.
See Gimbal_Interface::gimbal_status_t
structure for more details.
RAW_IMU (Message ID: #27)
The gimbal provides raw imu data for applications that want to inspect data and develop algorithms.
Acceleration (raw): range 4g = 8192.
Gyro(raw): range 1000dps = 32768.
Field
Type
Description
Gimbal Implementation
time_usec
uint64_t
Timestamp (us)
Same as official
xacc
int16_t
X acceleration (raw)
Same as official
yacc
int16_t
Y acceleration (raw)
Same as official
zacc
int16_t
Z acceleration (raw)
Same as official
xgyro
int16_t
Angular speed around the X-axis
Same as official
ygyro
int16_t
Angular speed around the Y-axis
Same as official
zgyro
int16_t
Angular speed around the Z-axis
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: 216 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)

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
set_limit_angle_pitch(constlimit_angle_t &limit_angle)
Sets the gimbal pitch axis limit.
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)
Sets the gimbal yaw axis limit.
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)
Sets the gimbal roll axis limit.
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.
Last updated
Was this helpful?