ardupilot/libraries/AP_HAL_SITL/RCInput.h

37 lines
827 B
C
Raw Normal View History

2012-12-17 23:56:21 -04:00
#pragma once
2012-12-17 23:56:21 -04:00
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define SITL_RC_INPUT_CHANNELS 16
#include "AP_HAL_SITL.h"
2012-12-17 23:56:21 -04:00
class HALSITL::RCInput : public AP_HAL::RCInput {
2012-12-17 23:56:21 -04:00
public:
RCInput(SITL_State *sitlState) {
_sitlState = sitlState;
2012-12-17 23:56:21 -04:00
}
void init() override;
bool new_input() override;
uint8_t num_channels() override {
return SITL_RC_INPUT_CHANNELS;
}
uint16_t read(uint8_t ch) override;
uint8_t read(uint16_t* periods, uint8_t len) override;
2012-12-17 23:56:21 -04:00
bool set_overrides(int16_t *overrides, uint8_t len) override;
bool set_override(uint8_t channel, int16_t override) override;
void clear_overrides() override;
2012-12-17 23:56:21 -04:00
private:
SITL_State *_sitlState;
bool _valid;
2012-12-17 23:56:21 -04:00
/* override state */
uint16_t _override[SITL_RC_INPUT_CHANNELS];
2012-12-17 23:56:21 -04:00
};
2012-12-18 05:04:47 -04:00
#endif
2012-12-17 23:56:21 -04:00