mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: fixed return value when no input
This commit is contained in:
parent
2ba0691d52
commit
8be59c73c7
|
@ -51,16 +51,14 @@ uint8_t AP_RCProtocol::num_channels()
|
||||||
{
|
{
|
||||||
if (_detected_protocol != AP_RCProtocol::NONE) {
|
if (_detected_protocol != AP_RCProtocol::NONE) {
|
||||||
return backend[_detected_protocol]->num_channels();
|
return backend[_detected_protocol]->num_channels();
|
||||||
} else {
|
|
||||||
return AP_RCProtocol::NONE;
|
|
||||||
}
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t AP_RCProtocol::read(uint8_t chan)
|
uint16_t AP_RCProtocol::read(uint8_t chan)
|
||||||
{
|
{
|
||||||
if (_detected_protocol != AP_RCProtocol::NONE) {
|
if (_detected_protocol != AP_RCProtocol::NONE) {
|
||||||
return backend[_detected_protocol]->read(chan);
|
return backend[_detected_protocol]->read(chan);
|
||||||
} else {
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue