mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_HAL_Linux: Remove RC overrides
This commit is contained in:
parent
627c7536f4
commit
737c4ac36f
@ -50,9 +50,6 @@ uint8_t RCInput::num_channels()
|
||||
|
||||
uint16_t RCInput::read(uint8_t ch)
|
||||
{
|
||||
if (_override[ch]) {
|
||||
return _override[ch];
|
||||
}
|
||||
if (ch >= _num_channels) {
|
||||
return 0;
|
||||
}
|
||||
@ -68,27 +65,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
||||
return len;
|
||||
}
|
||||
|
||||
bool RCInput::set_override(uint8_t channel, int16_t override)
|
||||
{
|
||||
if (override < 0) return false; /* -1: no change. */
|
||||
if (channel < LINUX_RC_INPUT_NUM_CHANNELS) {
|
||||
_override[channel] = override;
|
||||
if (override != 0) {
|
||||
rc_input_count++;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void RCInput::clear_overrides()
|
||||
{
|
||||
for (uint8_t i = 0; i < LINUX_RC_INPUT_NUM_CHANNELS; i++) {
|
||||
_override[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
process a PPM-sum pulse of the given width
|
||||
*/
|
||||
|
@ -26,9 +26,6 @@ public:
|
||||
return _rssi;
|
||||
}
|
||||
|
||||
bool set_override(uint8_t channel, int16_t override);
|
||||
void clear_overrides();
|
||||
|
||||
// default empty _timer_tick, this is overridden by board
|
||||
// specific implementations
|
||||
virtual void _timer_tick() {}
|
||||
@ -62,9 +59,6 @@ protected:
|
||||
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1);
|
||||
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1);
|
||||
|
||||
/* override state */
|
||||
uint16_t _override[LINUX_RC_INPUT_NUM_CHANNELS];
|
||||
|
||||
// state of ppm decoder
|
||||
struct {
|
||||
int8_t _channel_counter;
|
||||
|
Loading…
Reference in New Issue
Block a user