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