ardupilot/libraries/AP_HAL_SITL/RCInput.h

25 lines
513 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:
explicit RCInput(SITL_State *sitlState): _sitlState(sitlState) {}
void init() override;
bool new_input() override;
2018-07-23 23:46:31 -03:00
uint8_t num_channels() override;
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
private:
SITL_State *_sitlState;
};
2012-12-18 05:04:47 -04:00
#endif
2012-12-17 23:56:21 -04:00