HAL_Linux: added basic support for RC overrides

this allows for easier testing of RC output by allowing
mavproxy to setup fake inputs

Pair-Programmed-With: Sid, Anuj, Victor and Philip
This commit is contained in:
Andrew Tridgell 2014-06-27 20:29:14 +10:00
parent d79877792f
commit 72f94444c4
2 changed files with 63 additions and 28 deletions

View File

@ -5,42 +5,71 @@
#include "RCInput.h"
using namespace Linux;
LinuxRCInput::LinuxRCInput()
LinuxRCInput::LinuxRCInput() :
new_rc_input(false)
{}
void LinuxRCInput::init(void* machtnichts)
{}
bool LinuxRCInput::new_input() {
bool LinuxRCInput::new_input()
{
return new_rc_input;
}
uint8_t LinuxRCInput::num_channels()
{
return 8;
}
uint16_t LinuxRCInput::read(uint8_t ch)
{
new_rc_input = false;
if (_override[ch]) {
return _override[ch];
}
if (ch == 2) {
// force low throttle for now
return 900;
}
return 1500;
}
uint8_t LinuxRCInput::read(uint16_t* periods, uint8_t len)
{
for (uint8_t i=0; i<len; i++) {
periods[i] = read(i);
}
return 8;
}
bool LinuxRCInput::set_overrides(int16_t *overrides, uint8_t len)
{
bool res = false;
for (uint8_t i = 0; i < len; i++) {
res |= set_override(i, overrides[i]);
}
return res;
}
bool LinuxRCInput::set_override(uint8_t channel, int16_t override)
{
if (override < 0) return false; /* -1: no change. */
if (channel < 8) {
_override[channel] = override;
if (override != 0) {
new_rc_input = true;
return true;
}
}
return false;
}
uint8_t LinuxRCInput::num_channels() {
return 0;
}
uint16_t LinuxRCInput::read(uint8_t ch) {
if (ch == 2) return 900; /* throttle should be low, for safety */
else return 1500;
}
uint8_t LinuxRCInput::read(uint16_t* periods, uint8_t len) {
for (uint8_t i = 0; i < len; i++){
if (i == 2) periods[i] = 900;
else periods[i] = 1500;
}
return len;
}
bool LinuxRCInput::set_overrides(int16_t *overrides, uint8_t len) {
return true;
}
bool LinuxRCInput::set_override(uint8_t channel, int16_t override) {
return true;
}
void LinuxRCInput::clear_overrides()
{}
{
for (uint8_t i = 0; i < 8; i++) {
_override[i] = 0;
}
}
#endif // CONFIG_HAL_BOARD

View File

@ -16,6 +16,12 @@ public:
bool set_overrides(int16_t *overrides, uint8_t len);
bool set_override(uint8_t channel, int16_t override);
void clear_overrides();
private:
bool new_rc_input;
/* override state */
uint16_t _override[8];
};
#endif // __AP_HAL_LINUX_RCINPUT_H__