ardupilot/libraries/AP_HAL_Empty/RCInput.cpp

43 lines
786 B
C++
Raw Normal View History

2012-12-17 15:54:55 -04:00
#include "RCInput.h"
using namespace Empty;
EmptyRCInput::EmptyRCInput()
{}
void EmptyRCInput::init(void* machtnichts)
{}
bool EmptyRCInput::new_input() {
return false;
}
uint8_t EmptyRCInput::num_channels() {
2012-12-17 15:54:55 -04:00
return 0;
}
uint16_t EmptyRCInput::read(uint8_t ch) {
if (ch == 2) return 900; /* throttle should be low, for safety */
2012-12-17 15:54:55 -04:00
else return 1500;
}
uint8_t EmptyRCInput::read(uint16_t* periods, uint8_t len) {
for (uint8_t i = 0; i < len; i++){
if (i == 2) periods[i] = 900;
2012-12-17 15:54:55 -04:00
else periods[i] = 1500;
}
return len;
}
bool EmptyRCInput::set_overrides(int16_t *overrides, uint8_t len) {
return true;
}
bool EmptyRCInput::set_override(uint8_t channel, int16_t override) {
return true;
}
void EmptyRCInput::clear_overrides()
{}