Offboard gimbal control using MAVROS for object tracking

Jaeyoung Lim

Controlling a gimbal for object tracking is one of the essential functionalities for flying camera applications. A mount plugin was implemented in mavros to enable continuous control of gimbals from the companion computer.

The following video shows the gimbal controlled in order to look at a single ROI while following around a trajectory using a gimbal plugin.

humantracking.gif
The implementation of the example can be found in mavros_humantracking

How it works

The mount control interface can be controlled using the mavros_msgs::MountControl message. The message sends the MAV_CMD_DO_MOUNT_CONTROL to the flight controller to control the gimbal. The message is defined as below.

# MAVLink message: DO_MOUNT_CONTROL
# https://mavlink.io/en/messages/common.html#MAV_CMD_DO_MOUNT_CONTROL

std_msgs/Header header

uint8 mode # See enum MAV_MOUNT_MODE.
uint8 MAV_MOUNT_MODE_RETRACT = 0
uint8 MAV_MOUNT_MODE_NEUTRAL = 1
uint8 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2
uint8 MAV_MOUNT_MODE_RC_TARGETING = 3
uint8 MAV_MOUNT_MODE_GPS_POINT = 4

 float32 pitch # roll degrees or degrees/second depending on mount mode.
float32 roll # roll degrees or degrees/second depending on mount mode.
float32 yaw # roll degrees or degrees/second depending on mount mode.
float32 altitude  # altitude depending on mount mode.
float32 latitude # latitude in degrees * 1E7, set if appropriate mount mode.
float32 longitude # longitude in degrees * 1E7, set if appropriate mount mode.

The vmount mode is configured using the mavros_msgs::MountConfigure message. This message is mapped into the MAV_CMD_DO_MOUNT_CONFIGURE

# MAVLink message: DO_MOUNT_CONTROL
# https://mavlink.io/en/messages/common.html#MAV_CMD_DO_MOUNT_CONFIGURE

 std_msgs/Header header

 uint8 mode              # See enum MAV_MOUNT_MODE.
#MAV_MOUNT_MODE
uint8 MODE_RETRACT = 0
uint8 MODE_NEUTRAL = 1
uint8 MODE_MAVLINK_TARGETING = 2
uint8 MODE_RC_TARGETING = 3
uint8 MODE_GPS_POINT = 4

 bool stabilize_roll     # stabilize roll? (1 = yes, 0 = no)
bool stabilize_pitch    # stabilize pitch? (1 = yes, 0 = no)
bool stabilize_yaw      # stabilize yaw? (1 = yes, 0 = no)
uint8 roll_input        # roll input (See enum MOUNT_INPUT)
uint8 pitch_input       # pitch input (See enum MOUNT_INPUT)
uint8 yaw_input         # yaw input (See enum MOUNT_INPUT)

 #MOUNT_INPUT
uint8 INPUT_ANGLE_BODY_FRAME = 0
uint8 INPUT_ANGULAR_RATE = 1
uint8 INPUT_ANGLE_ABSOLUTE_FRAME = 2
---
bool success
# raw result returned by COMMAND_ACK
uint8 result

Reference

Pull requests relevent to this work
Add Mount Control plugin to control mount continuously #1257
Add mount mode with MAV_CMD_DO_MOUNT_CONFIGURE #1319

Leave a Reply

Fill in your details below or click an icon to log in:

WordPress.com Logo

You are commenting using your WordPress.com account. Log Out /  Change )

Twitter picture

You are commenting using your Twitter account. Log Out /  Change )

Facebook photo

You are commenting using your Facebook account. Log Out /  Change )

Connecting to %s