ardupilot/libraries/AP_HAL_AVR_SITL/RCInput.h
Andrew Tridgell 6eee2421cc AP_HAL: removed RCInput valid_channels() and added new_input() and num_channels()
the valid_channels() method was inconsistently implemented between
boards, and served two quite different purposes. It is clearer as two
functions
2014-03-25 14:39:41 +11:00

35 lines
793 B
C++

#ifndef __AP_HAL_AVR_SITL_RCINPUT_H__
#define __AP_HAL_AVR_SITL_RCINPUT_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#include <AP_HAL_AVR_SITL.h>
class AVR_SITL::SITLRCInput : public AP_HAL::RCInput {
public:
SITLRCInput(SITL_State *sitlState) {
_sitlState = sitlState;
}
void init(void* machtnichts);
bool new_input();
uint8_t num_channels() { return 8; }
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);
bool set_overrides(int16_t *overrides, uint8_t len);
bool set_override(uint8_t channel, int16_t override);
void clear_overrides();
private:
SITL_State *_sitlState;
bool _valid;
/* override state */
uint16_t _override[8];
};
#endif
#endif // __AP_HAL_AVR_SITL_RCINPUT_H__