RCOutput.h 841 B

1234567891011121314151617181920212223242526272829
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. #include "AP_HAL_SITL.h"
  5. class HALSITL::RCOutput : public AP_HAL::RCOutput {
  6. public:
  7. explicit RCOutput(SITL_State *sitlState): _sitlState(sitlState), _freq_hz(50) {}
  8. void init() override;
  9. void set_freq(uint32_t chmask, uint16_t freq_hz) override;
  10. uint16_t get_freq(uint8_t ch) override;
  11. void enable_ch(uint8_t ch) override;
  12. void disable_ch(uint8_t ch) override;
  13. void write(uint8_t ch, uint16_t period_us) override;
  14. uint16_t read(uint8_t ch) override;
  15. void read(uint16_t* period_us, uint8_t len) override;
  16. void cork(void) override;
  17. void push(void) override;
  18. private:
  19. SITL_State *_sitlState;
  20. uint16_t _freq_hz;
  21. uint16_t _enable_mask;
  22. bool _corked;
  23. uint16_t _pending[SITL_NUM_CHANNELS];
  24. };
  25. #endif