mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_SITL: Remove RC overrides
This commit is contained in:
parent
dc4f1786f6
commit
9c288df8d7
@ -9,7 +9,6 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
void RCInput::init()
|
||||
{
|
||||
clear_overrides();
|
||||
}
|
||||
|
||||
bool RCInput::new_input()
|
||||
@ -26,9 +25,6 @@ uint16_t RCInput::read(uint8_t ch)
|
||||
if (ch >= SITL_RC_INPUT_CHANNELS) {
|
||||
return 0;
|
||||
}
|
||||
if (_override[ch]) {
|
||||
return _override[ch];
|
||||
}
|
||||
return _sitlState->pwm_input[ch];
|
||||
}
|
||||
|
||||
@ -43,22 +39,4 @@ 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 < SITL_RC_INPUT_CHANNELS) {
|
||||
_override[channel] = static_cast<uint16_t>(override);
|
||||
if (override != 0) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void RCInput::clear_overrides()
|
||||
{
|
||||
memset(_override, 0, sizeof(_override));
|
||||
}
|
||||
#endif
|
||||
|
@ -18,14 +18,8 @@ public:
|
||||
uint16_t read(uint8_t ch) override;
|
||||
uint8_t read(uint16_t* periods, uint8_t len) override;
|
||||
|
||||
bool set_override(uint8_t channel, int16_t override) override;
|
||||
void clear_overrides() override;
|
||||
|
||||
private:
|
||||
SITL_State *_sitlState;
|
||||
|
||||
/* override state */
|
||||
uint16_t _override[SITL_RC_INPUT_CHANNELS];
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user