APM:Libraries
RCOutput.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3 
4 #include "RCOutput.h"
5 
6 #define ENABLE_DEBUG 0
7 
8 #if ENABLE_DEBUG
9 # include <stdio.h>
10 # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while (0)
11 #else
12 # define Debug(fmt, args ...)
13 #endif
14 
15 using namespace HALSITL;
16 
17 void RCOutput::init() {}
18 
19 void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
20 {
21  Debug("set_freq(0x%04x, %u)\n", static_cast<uint32_t>(chmask), static_cast<uint32_t>(freq_hz));
22  _freq_hz = freq_hz;
23 }
24 
25 uint16_t RCOutput::get_freq(uint8_t ch)
26 {
27  return _freq_hz;
28 }
29 
30 void RCOutput::enable_ch(uint8_t ch)
31 {
32  if (!(_enable_mask & (1U << ch))) {
33  Debug("enable_ch(%u)\n", ch);
34  }
35  _enable_mask |= 1U << ch;
36 }
37 
38 void RCOutput::disable_ch(uint8_t ch)
39 {
40  if (_enable_mask & (1U << ch)) {
41  Debug("disable_ch(%u)\n", ch);
42  }
43  _enable_mask &= ~1U << ch;
44 }
45 
46 void RCOutput::write(uint8_t ch, uint16_t period_us)
47 {
48  _sitlState->output_ready = true;
49  if (ch < SITL_NUM_CHANNELS && (_enable_mask & (1U<<ch))) {
50  if (_corked) {
51  _pending[ch] = period_us;
52  } else {
53  _sitlState->pwm_output[ch] = period_us;
54  }
55  }
56 }
57 
58 uint16_t RCOutput::read(uint8_t ch)
59 {
60  if (ch < SITL_NUM_CHANNELS) {
61  return _sitlState->pwm_output[ch];
62  }
63  return 0;
64 }
65 
66 void RCOutput::read(uint16_t* period_us, uint8_t len)
67 {
68  memcpy(period_us, _sitlState->pwm_output, len * sizeof(uint16_t));
69 }
70 
71 void RCOutput::cork(void)
72 {
73  if (!_corked) {
74  memcpy(_pending, _sitlState->pwm_output, SITL_NUM_CHANNELS * sizeof(uint16_t));
75  _corked = true;
76  }
77 }
78 
79 void RCOutput::push(void)
80 {
81  if (_corked) {
82  memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS * sizeof(uint16_t));
83  _corked = false;
84  }
85 }
86 
87 #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
#define Debug(fmt, args ...)
Definition: RCOutput.cpp:12
uint16_t _enable_mask
Definition: RCOutput.h:24
uint16_t read(uint8_t ch) override
void disable_ch(uint8_t ch) override
uint16_t pwm_output[SITL_NUM_CHANNELS]
Definition: SITL_State.h:47
void init() override
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