ardupilot/libraries/AP_HAL_SITL/RCOutput.h

32 lines
764 B
C
Raw Normal View History

2012-12-17 23:56:21 -04:00
#ifndef __AP_HAL_SITL_RCOUTPUT_H__
#define __AP_HAL_SITL_RCOUTPUT_H__
2012-12-17 23:56:21 -04:00
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_HAL_SITL.h"
2012-12-17 23:56:21 -04:00
class HALSITL::SITLRCOutput : public AP_HAL::RCOutput {
2012-12-17 23:56:21 -04:00
public:
SITLRCOutput(SITL_State *sitlState) {
_sitlState = sitlState;
_freq_hz = 50;
2012-12-17 23:56:21 -04:00
}
void init();
2012-12-17 23:56:21 -04:00
void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch);
void enable_ch(uint8_t ch);
void disable_ch(uint8_t ch);
void write(uint8_t ch, uint16_t period_us);
uint16_t read(uint8_t ch);
void read(uint16_t* period_us, uint8_t len);
private:
2012-12-17 23:56:21 -04:00
SITL_State *_sitlState;
uint16_t _freq_hz;
};
2012-12-18 05:04:47 -04:00
#endif
#endif // __AP_HAL_SITL_RCOUTPUT_H__
2012-12-17 23:56:21 -04:00