AP_RCProtocol: Reject invalid rc input values from transmitter
I noticed during PX4-Autopilot development that transmitters can output invalid RC values. PX4 filters them in the INPUT_RC driver, but ArduPilot did not. After seeing similar reports in the ArduPilot Japan community, I added a fix in IOMCU to reject invalid RC inputs and prevent unexpected behavior.
I received a flight log from a user and performed an analysis. Through the log analysis, I discovered RC input values that were outside the calibrated MIN–MAX range.
CH5 : 961 CH9: 2085
@Hwurzburg san If the throttle PWM value is lower than the MIN value, it is treated as a valid input. This condition has been properly taken into account.
if (i == thr_idx && v < ch->get_radio_min()) {
continue;
}
@Hwurzburg san I’m saying that if a transmitter sends invalid values, then that transmitter should not be used — but that’s not the right approach. If the transmitter sends invalid values, ArduPilot should filter them instead. Transmitters send channel values cyclically at 100 Hz, 70 Hz, or similar rates.
Please explain the disadvantages of excluding those values.
ArduPilot detects a radio failure if it cannot receive valid data continuously for 500 milliseconds. If the receiver or transmitter sends invalid values for 500 milliseconds, it will be recognized as a radio failure. During this period, ArduPilot continues to use the previous values for up to 500 milliseconds, which is quite a long time.
Since SBUS transmits offset values for all channels, I believe it’s acceptable to exclude the entire frame if even a single invalid value is detected.
I want to resolve this issue as soon as possible. I have already experienced this phenomenon with a transmitter from a certain manufacturer. When a flight mode is assigned to a switch, the flight mode suddenly changes. Since ArduPilot does not verify the switch state against the current flight mode, it does not return to the original mode.
As an emergency measure, we have assigned a channel for forced disarm. If an invalid value triggers a forced disarm, the aircraft will crash.
We want to reduce the risk of treating invalid values as valid ones.
Hi @muramura,
Thanks very much for the PR. I'm sure we can get this or an equivalent fix into 4.7.
BTW it's unfortunate that SBUS doesn't include a CRC byte. It's somewhat amazing that such a widely used and trusted protocol wouldn't have such an easy way to allow the receiver to reject errors.
@rmackay9 san SBUS uses only simple error detection with EVEN parity. If the transmitter sends an incorrect PWM OFFSET value in the SBUS frame, it will not result in a CRC error.
There are cases where the RC receiver may output values that are outside the transmitter’s calibrated range. This can occur due to receiver malfunction, regardless of the specific underlying cause.
In my system, certain channels are assigned to critical functions such as forced disarm, flight-mode selection, and the agricultural spraying pump. If the receiver outputs invalid or abnormal values, ArduPilot may perform unintended or unsafe actions.
Therefore, it is important to recognize that an RC receiver may sometimes send invalid values because of operational malfunction, even when the transmitter is correctly calibrated.
if your SBUS receiver can malfunction and send channel values outside of the calibrated range setup using the tx and cause critical errors, then it can malfunction and send incorrect values within the range and cause critical errors also....no way to protect against that...the obvious solution is to use a higher reliability receiver system
since many people use SBUS systems, and have disarm switches or other critical items, I am surprised this has not been an issue reported in the past....
@Hwurzburg san
Thank you for the feedback. I understand that a malfunctioning receiver might also output incorrect values within the calibrated range, and that ArduPilot cannot fully protect against that.
However, the issue here is different. Some SBUS receivers (e.g., SIYI, Skydroid) implement SBUS based on reverse-engineered specifications, since Futaba has never published the official protocol. Because of this, they occasionally output transient values that are impossible according to the SBUS specification—far outside the valid range.
ArduPilot currently accepts these frames as normal values, which can trigger critical functions such as forced disarm, flight-mode switching, or the spray pump.
We cannot protect against all receiver failures, but we can safely reject these clearly invalid, out-of-range protocol values at the RC_PROTOCOL layer. This does not solve every problem, but it eliminates a known and preventable source of unsafe behavior.
at best, this could be an option....rejecting RC values outside of min/max cannot be normal behavior since its very possible the TX could exceed these limits over temp/voltage and therefore loss of RC control would result...
@Hwurzburg san
I understand your point. If rejecting out-of-range values is a concern for some users, then making this behavior optional is a reasonable solution. Users who want additional protection can enable the filter, and users who prefer not to use it can leave it disabled.
@Hwurzburg san
I added the configuration parameter RC_PWMCHK and made the feature optional.
@Hwurzburg san I added PWM_CHECK_VALUE to RC_OPTIONS.
if your SBUS receiver can malfunction and send channel values outside of the calibrated range setup using the tx and cause critical errors, then it can malfunction and send incorrect values within the range and cause critical errors also....no way to protect against that...the obvious solution is to use a higher reliability receiver system
since many people use SBUS systems, and have disarm switches or other critical items, I am surprised this has not been an issue reported in the past....
This. Why is this a problem now?
The one graph shown in support of this seems to be a case of invalid values set up in a bind-time-values receiver failsafe.
There are cases where the RC receiver may output values that are outside the transmitter’s calibrated range. This can occur due to receiver malfunction, regardless of the specific underlying cause.
Log, please.
@peterbarker san
Could you tell me which specific log fields are required? Because the global position is already recorded in the log, I would like to narrow down the fields to only what is necessary.
@peterbarker san
Could you tell me which specific log fields are required? Because the global position is already recorded in the log, I would like to narrow down the fields to only what is necessary.
RCIN, RCI2, MSG, EV, FMT, FMTU, MULT, UNIT
... and the ones I've forgotten.
@peterbarker san THIS FILTERED LOG: https://github.com/ArduPilot/ardupilot/blob/196ed4b244cd18e969d9868590b3c442d3a2b02e/libraries/RC_Channel/filtered.log