AP_RCProtocol: fixed return value when no input

This commit is contained in:
Andrew Tridgell 2018-01-18 09:02:42 +11:00
parent 2ba0691d52
commit 8be59c73c7
1 changed files with 2 additions and 4 deletions

View File

@ -51,16 +51,14 @@ uint8_t AP_RCProtocol::num_channels()
{
if (_detected_protocol != AP_RCProtocol::NONE) {
return backend[_detected_protocol]->num_channels();
} else {
return AP_RCProtocol::NONE;
}
return 0;
}
uint16_t AP_RCProtocol::read(uint8_t chan)
{
if (_detected_protocol != AP_RCProtocol::NONE) {
return backend[_detected_protocol]->read(chan);
} else {
return 0;
}
return 0;
}