mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_PX4: Remove RC overrides
This commit is contained in:
parent
737c4ac36f
commit
4d83644bd6
@ -21,7 +21,6 @@ void PX4RCInput::init()
|
||||
if (_rc_sub == -1) {
|
||||
AP_HAL::panic("Unable to subscribe to input_rc");
|
||||
}
|
||||
clear_overrides();
|
||||
pthread_mutex_init(&rcin_mutex, nullptr);
|
||||
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
@ -40,12 +39,7 @@ bool PX4RCInput::new_input()
|
||||
// don't consider input valid if we are in RC failsafe.
|
||||
valid = false;
|
||||
}
|
||||
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;
|
||||
pthread_mutex_unlock(&rcin_mutex);
|
||||
if (_rcin.input_source != last_input_source) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", input_source_name(_rcin.input_source));
|
||||
@ -64,19 +58,10 @@ uint8_t PX4RCInput::num_channels()
|
||||
|
||||
uint16_t PX4RCInput::read(uint8_t ch)
|
||||
{
|
||||
if (ch >= RC_INPUT_MAX_CHANNELS) {
|
||||
if (ch >= MIN(RC_INPUT_MAX_CHANNELS, _rcin.channel_count)) {
|
||||
return 0;
|
||||
}
|
||||
pthread_mutex_lock(&rcin_mutex);
|
||||
if (_override[ch]) {
|
||||
uint16_t v = _override[ch];
|
||||
pthread_mutex_unlock(&rcin_mutex);
|
||||
return v;
|
||||
}
|
||||
if (ch >= _rcin.channel_count) {
|
||||
pthread_mutex_unlock(&rcin_mutex);
|
||||
return 0;
|
||||
}
|
||||
uint16_t v = _rcin.values[ch];
|
||||
pthread_mutex_unlock(&rcin_mutex);
|
||||
|
||||
@ -101,28 +86,6 @@ uint8_t PX4RCInput::read(uint16_t* periods, uint8_t len)
|
||||
return len;
|
||||
}
|
||||
|
||||
bool PX4RCInput::set_override(uint8_t channel, int16_t override) {
|
||||
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 PX4RCInput::clear_overrides()
|
||||
{
|
||||
for (uint8_t i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
|
||||
set_override(i, 0);
|
||||
}
|
||||
}
|
||||
|
||||
const char *PX4RCInput::input_source_name(uint8_t id) const
|
||||
{
|
||||
switch(id) {
|
||||
|
@ -8,7 +8,7 @@
|
||||
|
||||
|
||||
#ifndef RC_INPUT_MAX_CHANNELS
|
||||
#define RC_INPUT_MAX_CHANNELS 18
|
||||
#define RC_INPUT_MAX_CHANNELS 18u
|
||||
#endif
|
||||
|
||||
class PX4::PX4RCInput : public AP_HAL::RCInput {
|
||||
@ -23,21 +23,15 @@ 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];
|
||||
struct rc_input_values _rcin;
|
||||
int _rc_sub;
|
||||
uint64_t _last_read;
|
||||
bool _override_valid;
|
||||
perf_counter_t _perf_rcin;
|
||||
pthread_mutex_t rcin_mutex;
|
||||
int16_t _rssi = -1;
|
||||
|
Loading…
Reference in New Issue
Block a user