mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_HAL_ChibiOS: Remove RC overrides
This commit is contained in:
parent
4d83644bd6
commit
593da25a7a
@ -25,6 +25,8 @@
|
||||
extern AP_IOMCU iomcu;
|
||||
#endif
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#define SIG_DETECT_TIMEOUT_US 500000
|
||||
using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -54,12 +56,7 @@ bool RCInput::new_input()
|
||||
}
|
||||
bool valid = _rcin_timestamp_last_signal != _last_read;
|
||||
|
||||
if (_override_valid) {
|
||||
// if we have RC overrides active, then always consider it valid
|
||||
valid = true;
|
||||
}
|
||||
_last_read = _rcin_timestamp_last_signal;
|
||||
_override_valid = false;
|
||||
rcin_mutex.give();
|
||||
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
@ -84,22 +81,10 @@ uint8_t RCInput::num_channels()
|
||||
|
||||
uint16_t RCInput::read(uint8_t channel)
|
||||
{
|
||||
if (!_init) {
|
||||
return 0;
|
||||
}
|
||||
if (channel >= RC_INPUT_MAX_CHANNELS) {
|
||||
if (!_init || (channel >= MIN(RC_INPUT_MAX_CHANNELS, _num_channels))) {
|
||||
return 0;
|
||||
}
|
||||
rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||
if (_override[channel]) {
|
||||
uint16_t v = _override[channel];
|
||||
rcin_mutex.give();
|
||||
return v;
|
||||
}
|
||||
if (channel >= _num_channels) {
|
||||
rcin_mutex.give();
|
||||
return 0;
|
||||
}
|
||||
uint16_t v = _rc_values[channel];
|
||||
rcin_mutex.give();
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
@ -126,34 +111,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
||||
return len;
|
||||
}
|
||||
|
||||
bool RCInput::set_override(uint8_t channel, int16_t override)
|
||||
{
|
||||
if (!_init) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (override < 0) {
|
||||
return false; /* -1: no change. */
|
||||
}
|
||||
if (channel >= RC_INPUT_MAX_CHANNELS) {
|
||||
return false;
|
||||
}
|
||||
_override[channel] = override;
|
||||
if (override != 0) {
|
||||
_override_valid = true;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void RCInput::clear_overrides()
|
||||
{
|
||||
for (uint8_t i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
|
||||
set_override(i, 0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void RCInput::_timer_tick(void)
|
||||
{
|
||||
if (!_init) {
|
||||
|
@ -50,20 +50,13 @@ public:
|
||||
return _rssi;
|
||||
}
|
||||
|
||||
|
||||
bool set_override(uint8_t channel, int16_t override) override;
|
||||
void clear_overrides() override;
|
||||
|
||||
void _timer_tick(void);
|
||||
bool rc_bind(int dsmMode) override;
|
||||
|
||||
private:
|
||||
/* override state */
|
||||
uint16_t _override[RC_INPUT_MAX_CHANNELS];
|
||||
uint16_t _rc_values[RC_INPUT_MAX_CHANNELS] = {0};
|
||||
|
||||
uint64_t _last_read;
|
||||
bool _override_valid;
|
||||
uint8_t _num_channels;
|
||||
Semaphore rcin_mutex;
|
||||
int16_t _rssi = -1;
|
||||
|
Loading…
Reference in New Issue
Block a user