APM:Libraries
RCOutput.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
5 #include "AP_HAL_SITL.h"
6 
8 public:
9  explicit RCOutput(SITL_State *sitlState): _sitlState(sitlState), _freq_hz(50) {}
10  void init() override;
11  void set_freq(uint32_t chmask, uint16_t freq_hz) override;
12  uint16_t get_freq(uint8_t ch) override;
13  void enable_ch(uint8_t ch) override;
14  void disable_ch(uint8_t ch) override;
15  void write(uint8_t ch, uint16_t period_us) override;
16  uint16_t read(uint8_t ch) override;
17  void read(uint16_t* period_us, uint8_t len) override;
18  void cork(void);
19  void push(void);
20 
21 private:
23  uint16_t _freq_hz;
24  uint16_t _enable_mask;
25  bool _corked;
27 };
28 
29 #endif
uint16_t _freq_hz
Definition: RCOutput.h:23
#define SITL_NUM_CHANNELS
Definition: SITL.h:35
void write(uint8_t ch, uint16_t period_us) override
RCOutput(SITL_State *sitlState)
Definition: RCOutput.h:9
uint16_t _enable_mask
Definition: RCOutput.h:24
uint16_t read(uint8_t ch) override
void disable_ch(uint8_t ch) override
void init() override
static SITL_State sitlState
void enable_ch(uint8_t ch) override
uint16_t _pending[SITL_NUM_CHANNELS]
Definition: RCOutput.h:26
SITL_State * _sitlState
Definition: RCOutput.h:22
void set_freq(uint32_t chmask, uint16_t freq_hz) override
uint16_t get_freq(uint8_t ch) override