2012-12-17 23:56:21 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
#ifndef __AP_HAL_SITL_RCINPUT_H__
|
|
|
|
#define __AP_HAL_SITL_RCINPUT_H__
|
2012-12-17 23:56:21 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-05-04 03:15:12 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_SITL.h"
|
2012-12-17 23:56:21 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
class HALSITL::SITLRCInput : public AP_HAL::RCInput {
|
2012-12-17 23:56:21 -04:00
|
|
|
public:
|
|
|
|
SITLRCInput(SITL_State *sitlState) {
|
2015-05-04 21:59:07 -03:00
|
|
|
_sitlState = sitlState;
|
2012-12-17 23:56:21 -04:00
|
|
|
}
|
|
|
|
void init(void* machtnichts);
|
2014-03-25 00:39:41 -03:00
|
|
|
bool new_input();
|
2015-05-04 21:59:07 -03:00
|
|
|
uint8_t num_channels() {
|
|
|
|
return 8;
|
|
|
|
}
|
2012-12-17 23:56:21 -04:00
|
|
|
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();
|
2012-12-18 06:14:32 -04:00
|
|
|
|
2012-12-17 23:56:21 -04:00
|
|
|
private:
|
|
|
|
SITL_State *_sitlState;
|
2012-12-18 06:14:32 -04:00
|
|
|
bool _valid;
|
2012-12-17 23:56:21 -04:00
|
|
|
|
|
|
|
/* override state */
|
|
|
|
uint16_t _override[8];
|
|
|
|
};
|
|
|
|
|
2012-12-18 05:04:47 -04:00
|
|
|
#endif
|
2015-05-04 03:15:12 -03:00
|
|
|
#endif // __AP_HAL_SITL_RCINPUT_H__
|
2012-12-17 23:56:21 -04:00
|
|
|
|