Move a Servo

This page explains how MAVLink can be used by a ground station or companion computer to move a servo. The user wiki pages for servos is here.

Set the Servo position with MAV_CMD_DO_SET_SERVO

The servo’s position can be set by sending a COMMAND_LONG with the command, param1 and param2 fields set as specified for the MAV_CMD_DO_SET_SERVO command.

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_SET_SERVO=183
confirmation uint8_t 0
param1 float Servo instance number
param2 float PWM (normally between 1000 and 2000)
param3 float not used
param4 float not used
param5 float not used
param6 float not used
param7 float not used

Note

“ServoRelayEvent: Channel x is already in use” will be displayed if you try to move a servo that is configured for use as a control surface or for some other feature. Check the SERVOx_FUNCTION parameter value and ensure it is 0 (“Disabled”), 1 (“RCPassThru”), 22 (“SprayerPump”), 23 (“SprayerSpinner”), or between 51 (“RCIN1”) and 66 (“RCIN16”)

Example

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

  • module load graph

  • graph SERVO_OUTPUT_RAW.servo8_raw

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 183 0 8 1200 0 0 0 0 0

Move servo output 8 to 1200

Cycle the Servo position with MAV_CMD_DO_REPEAT_SERVO

The servo’s position can be set to cycle (i.e. toggle) between a PWM value and SERVOx_TRIM by sending a COMMAND_LONG with fields set as specified for the MAV_CMD_DO_REPEAT_SERVO command.

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_REPEAT_SERVO=184
confirmation uint8_t 0
param1 float Servo instance number
param2 float PWM (normally between 1000 and 2000)
param3 float Cycle count
param4 float Cycle time (in milliseconds)
param5 float not used
param6 float not used
param7 float not used

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

  • module load graph

  • graph SERVO_OUTPUT_RAW.servo8_raw

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 184 0 8 1200 3 1000 0 0 0

Cycle servo output 8 between 1200 and 1500 3 times at 1hz