mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_QURT: Remove set_overrides() method
This commit is contained in:
parent
f9d1574f73
commit
299543bd35
|
@ -101,18 +101,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
|||
return (i+1);
|
||||
}
|
||||
|
||||
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
|
||||
{
|
||||
bool res = false;
|
||||
if(len > QURT_RC_INPUT_NUM_CHANNELS){
|
||||
len = QURT_RC_INPUT_NUM_CHANNELS;
|
||||
}
|
||||
for (uint8_t i = 0; i < len; i++) {
|
||||
res |= set_override(i, overrides[i]);
|
||||
}
|
||||
return res;
|
||||
}
|
||||
|
||||
bool RCInput::set_override(uint8_t channel, int16_t override)
|
||||
{
|
||||
if (override < 0) return false; /* -1: no change. */
|
||||
|
|
|
@ -22,7 +22,6 @@ public:
|
|||
uint16_t read(uint8_t ch);
|
||||
uint8_t read(uint16_t* periods, uint8_t len);
|
||||
|
||||
bool set_overrides(int16_t *overrides, uint8_t len);
|
||||
bool set_override(uint8_t channel, int16_t override);
|
||||
void clear_overrides();
|
||||
|
||||
|
|
Loading…
Reference in New Issue