mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_Linux: Remove set_overrides() method
This commit is contained in:
parent
d54ef79798
commit
517e20093e
@ -68,18 +68,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
|||||||
return len;
|
return len;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
|
|
||||||
{
|
|
||||||
bool res = false;
|
|
||||||
if(len > LINUX_RC_INPUT_NUM_CHANNELS){
|
|
||||||
len = LINUX_RC_INPUT_NUM_CHANNELS;
|
|
||||||
}
|
|
||||||
for (uint8_t i = 0; i < len; i++) {
|
|
||||||
res |= set_override(i, overrides[i]);
|
|
||||||
}
|
|
||||||
return res;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool RCInput::set_override(uint8_t channel, int16_t override)
|
bool RCInput::set_override(uint8_t channel, int16_t override)
|
||||||
{
|
{
|
||||||
if (override < 0) return false; /* -1: no change. */
|
if (override < 0) return false; /* -1: no change. */
|
||||||
|
@ -26,7 +26,6 @@ public:
|
|||||||
return _rssi;
|
return _rssi;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool set_overrides(int16_t *overrides, uint8_t len);
|
|
||||||
bool set_override(uint8_t channel, int16_t override);
|
bool set_override(uint8_t channel, int16_t override);
|
||||||
void clear_overrides();
|
void clear_overrides();
|
||||||
|
|
||||||
|
@ -19,6 +19,8 @@
|
|||||||
*/
|
*/
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#include <RC_Channel/RC_Channel.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||||
|
|
||||||
#include "RCOutput_qflight.h"
|
#include "RCOutput_qflight.h"
|
||||||
@ -166,7 +168,13 @@ void RCOutput_QFLIGHT::check_rc_in(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (have_data) {
|
if (have_data) {
|
||||||
hal.rcin->set_overrides((int16_t*)rcu.rcin.rcin, 8);
|
// FIXME: This is an incredibly dirty hack as this probhibits the usage of
|
||||||
|
// overrides if an RC reciever is connected, as the next RC input will
|
||||||
|
// stomp over the GCS set overrides. This results in incredibly confusing,
|
||||||
|
// undocumented behaviour, that cannot be reported to the user.
|
||||||
|
for (uint8_t i = 0; i < 8; i++) {
|
||||||
|
RC_Channels::set_override(i, rcu.rcin.rcin[i]);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
nrcin_bytes = 0;
|
nrcin_bytes = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user