RC Input (aka Pilot Input)¶
Traditionally the pilot’s manual input via an RC transmitter is sent to the autopilot via a separate wireless link but it can alternatively be sent via MAVLink. This page describes the messages that can be used and gives advice on some potential issues
For reference here are some user focused RC related wiki pages:
The autopilot will ignore the RC input messages if the sender’s system id does not match the autopilot’s SYSID_MYGCS and SYSID_ENFORCE = 1
RC input via MAVlink typically results in a laggy response caused by telemetry system lag and/or bandwidth limitations (these messages normally share bandwidth with other MAVLink messages passed between GCS and the vehicle)
The Pilot’s RC inputs can be monitored by the GCS or companion computer via the RC_CHANNELS message
RC_CHANNELS_OVERRIDE¶
The RC_CHANNELS_OVERRIDE message allows setting the PWM equivalent value for each channel. This is normally a value between 1000 and 2000 but ArduPilot’s RC input library uses the RCx_MIN, RCx_MAX and RCx_TRIM parameters to scale the input. Note though that these parameters are normally set by the user during the RC Calibration stage.
If both a regular transmitter (e.g. Futaba, Spektrum, etc) which sends actualy PWM values and a MAVLink enabled RC input system (sending messages via one of the message listed on this page) then care should be taken to ensure the RCx_MIN/MAX ranges are consistent between the two systems. If the MAVLink RC input stops, ArduPilot falls back to regular RC input within a few seconds. This timeout is configurable using the RC_OVERRIDE_TIME parameter.
Be careful not to change the flight mode inadvertently. By default either channel 5 or channel 8 (depending upon the vehicle type) is used to set the flight mode but this can be disabled by setting FLTMODE_CH or MODE_CH to 0
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 |
chan1_raw | uint16_t | RC channel 1 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX (e.g 65535) to ignore this field |
chan2_raw | uint16_t | RC channel 2 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan3_raw | uint16_t | RC channel 3 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan4_raw | uint16_t | RC channel 4 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan5_raw | uint16_t | RC channel 5 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan6_raw | uint16_t | RC channel 6 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan7_raw | uint16_t | RC channel 7 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan8_raw | uint16_t | RC channel 8 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan9_raw | uint16_t | RC channel 9 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan10_raw | uint16_t | RC channel 10 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan11_raw | uint16_t | RC channel 11 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan12_raw | uint16_t | RC channel 12 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan13_raw | uint16_t | RC channel 13 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan14_raw | uint16_t | RC channel 14 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan15_raw | uint16_t | RC channel 15 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan16_raw | uint16_t | RC channel 16 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan17_raw | uint16_t | RC channel 17 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
chan18_raw | uint16_t | RC channel 18 value. Normally 1000 ~ 2000, 0 to release channel back to the RC radio, UINT16_MAX to ignore this field |
Example
The example commands below can be copy-pasted into MAVProxy (aka SITL) to test the message. Before running these commands enter:
module load message
graph RC_CHANNELS.chan1_raw RC_CHANNELS.chan2_raw RC_CHANNELS.chan3_raw RC_CHANNELS.chan4_raw RC_CHANNELS.chan7_raw
During simulator testing it may be useful to enable/disable the RC failsafe by setting FS_THR_ENABLE = 0 and/or simulate an RC failure by setting SIM_RC_FAIL = 1
Example MAVProxy/SITL Command |
Description |
---|---|
|
Set channels 1 ~ 4 to 1500 |
|
Set ch1 (roll) to 1800 (e.g. roll right) |
|
Set ch2 (pitch) to 1200 (e.g. pitch forward) |
|
Set ch3 (throttle) to 1800 (e.g. climb) |
|
Set ch4 (yaw) to 1800 (e.g. rotate clockwise) |
|
Set ch4 (yaw) to 1800, all other channels from normal RC |
|
Set ch7 to 1800, all other channels from normal RC |
|
Set ch7 to 1800, all other channels unchanged |
MANUAL_CONTROL¶
The MANUAL_CONTROL message allows sending roll, pitch, throttle and yaw values as normalised values between -1000 and +1000 and avoids any potential issues with channel mapping or PWM input ranges
Command Field | Type | Description |
---|---|---|
target | uint8_t | System ID of flight controller (e.g. 1) |
x | int16_t | X-axis / Pitch, normally -1000 (backwards) ~ +1000 (forwards), INT16_MAX (32767) if this axis is invalid |
y | int16_t | Y-axis / Roll, normally -1000 (left) ~ +1000 (right), INT16_MAX if this axis is invalid |
z | int16_t | Z-axis / Thrust, normally 0 (down) ~ +1000 (up), INT16_MAX if this axis is invalid |
r | int16_t | R-axis / Yaw, normally -1000 (counter-clockwise) ~ +1000 (clockwise), INT16_MAX if this axis is invalid |
buttons | uint16_t | not used |
buttons2 | uint16_t | not used |
enabled_extensions | uint8_t | not used |
s | int16_t | not used |
t | int16_t | not used |
aux1 | int16_t | not used |
aux2 | int16_t | not used |
aux3 | int16_t | not used |
aux4 | int16_t | not used |
aux5 | int16_t | not used |
aux6 | int16_t | not used |
Example
The example commands below can be copy-pasted into MAVProxy (aka SITL) to test the message. Before running these commands enter:
module load message
Example MAVProxy/SITL Command |
Description |
---|---|
|
Pitch forward 30%, Throttle 50% |
|
Roll right 30%, Throttle 50% |
|
Throttle 100% |
|
Yaw right 10%, Throttle 50% |
|
Yaw right 10%, all others unchanged |
Auxiliary Functions¶
Auxiliary functions can be executed by sending a COMMAND_LONG or COMMAND_INT message with the “command” field set to MAV_CMD_DO_AUX_FUNCTION (e.g. 218)
“param1” should be set to the auxiliary function. The full list of available functions can be found here on the user focused Auxiliary Functions page
“param2” should be set to 0:Switch Low (e.g deactivate function), 1:Switch Middle or 2:Switch Highs (e.g. activate function)
The example commands below can be copy-pasted into MAVProxy (aka SITL) to test the message. Before running these commands enter:
module load message
Example MAVProxy/SITL Command |
Description |
---|---|
|
RC Overrides Enable |
|
RC Overrides Disable |
|
GPS Disable |
|
GPS Enable |
Effect on Failsafes¶
It may be necessary to extend the RC failsafe timeout due to lag and loss of messages on the telemetry link. This can be done by increasing the RC_FS_TIMEOUT parameter
Handling both Regular RC and MAVLink RC input¶
If MAVLink based RC input is sent from the GCS this will generally override the regular RC input. If the MAVLink RC input stops, ArduPilot falls back to regular RC input within a few seconds. This timeout is configurable using the RC_OVERRIDE_TIME parameter.
The “RC Override Enable” auxiliary switch can be used to allow a pilot with a regular RC to forcibly disable any MAVLink RC input
The RC_OPTIONS parameter includes an “Ignore MAVLink Overrides” option that can be used to more permanently disable MAVLink RC input