APM:Libraries
RCOutput.h
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #pragma once
18 
19 #include "AP_HAL_ChibiOS.h"
20 #include "shared_dma.h"
21 #include "ch.h"
22 #include "hal.h"
23 
24 #if HAL_USE_PWM == TRUE
25 
27 public:
28  void init();
29  void set_freq(uint32_t chmask, uint16_t freq_hz);
30  uint16_t get_freq(uint8_t ch);
31  void enable_ch(uint8_t ch);
32  void disable_ch(uint8_t ch);
33  void write(uint8_t ch, uint16_t period_us);
34  uint16_t read(uint8_t ch);
35  void read(uint16_t* period_us, uint8_t len);
36  uint16_t read_last_sent(uint8_t ch) override;
37  void read_last_sent(uint16_t* period_us, uint8_t len) override;
38  void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
39  _esc_pwm_min = min_pwm;
40  _esc_pwm_max = max_pwm;
41  }
42  bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) override {
43  min_pwm = _esc_pwm_min;
44  max_pwm = _esc_pwm_max;
45  return true;
46  }
47  void set_output_mode(uint16_t mask, enum output_mode mode) override;
48 
49  float scale_esc_to_unity(uint16_t pwm) override {
50  return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0;
51  }
52 
53  void cork(void) override;
54  void push(void) override;
55 
56  /*
57  force the safety switch on, disabling PWM output from the IO board
58  */
59  bool force_safety_on(void) override;
60 
61  /*
62  force the safety switch off, enabling PWM output from the IO board
63  */
64  void force_safety_off(void) override;
65 
66  /*
67  set PWM to send to a set of channels when the safety switch is
68  in the safe state
69  */
70  void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
71 
72  bool enable_px4io_sbus_out(uint16_t rate_hz) override;
73 
74  /*
75  set default update rate
76  */
77  void set_default_rate(uint16_t rate_hz) override;
78 
79  /*
80  timer push (for oneshot min rate)
81  */
82  void timer_tick(void) override;
83 
84  /*
85  setup for serial output to a set of ESCs, using the given
86  baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
87  databits. This is used for ESC configuration and firmware
88  flashing
89  */
90  bool setup_serial_output(uint16_t chan_mask, ByteBuffer *buffer, uint32_t baudrate);
91 
92  /*
93  setup for serial output to an ESC using the given
94  baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
95  databits. This is used for passthrough ESC configuration and
96  firmware flashing
97 
98  While serial output is active normal output to this channel is
99  suspended. Output to some other channels (such as those in the
100  same channel timer group) may also be stopped, depending on the
101  implementation
102  */
103  bool serial_setup_output(uint8_t chan, uint32_t baudrate) override;
104 
105  /*
106  write a set of bytes to an ESC, using settings from
107  serial_setup_output. This is a blocking call
108  */
109  bool serial_write_bytes(const uint8_t *bytes, uint16_t len) override;
110 
111  /*
112  read a byte from a port, using serial parameters from serial_setup_output()
113  return the number of bytes read
114  */
115  uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) override;
116 
117  /*
118  stop serial output. This restores the previous output mode for
119  the channel and any other channels that were stopped by
120  serial_setup_output()
121  */
122  void serial_end(void) override;
123 
124  /*
125  enable telemetry request for a mask of channels. This is used
126  with DShot to get telemetry feedback
127  */
128  void set_telem_request_mask(uint16_t mask) { telem_request_mask = (mask >> chan_offset); }
129 
130  /*
131  get safety switch state, used by Util.cpp
132  */
134 
135 private:
136  struct pwm_group {
137  // only advanced timers can do high clocks needed for more than 400Hz
139  uint8_t chan[4]; // chan number, zero based, 255 for disabled
140  PWMConfig pwm_cfg;
141  PWMDriver* pwm_drv;
142  bool have_up_dma; // can we do DMAR outputs for DShot?
144  uint8_t dma_up_channel;
145  uint8_t alt_functions[4];
146  ioline_t pal_lines[4];
147 
148  // below this line is not initialised by hwdef.h
150  uint16_t frequency_hz;
151  uint16_t ch_mask;
152  const stm32_dma_stream_t *dma;
154  uint32_t *dma_buffer;
155  bool have_lock;
157  uint32_t bit_width_mul;
158  uint32_t rc_frequency;
161 
162  // serial output
163  struct {
164  // expected time per bit
165  uint32_t bit_time_us;
166 
167  // channel to output to within group (0 to 3)
168  uint8_t chan;
169 
170  // thread waiting for byte to be written
171  thread_t *waiter;
172  } serial;
173  };
174 
175  /*
176  structure for IRQ handler for soft-serial input
177  */
178  static struct irq_state {
179  // ioline for port being read
180  ioline_t line;
181 
182  // time the current byte started
183  systime_t byte_start_tick;
184 
185  // number of bits we have read in this byte
186  uint8_t nbits;
187 
188  // bitmask of bits so far (includes start and stop bits)
189  uint16_t bitmask;
190 
191  // value of completed byte (includes start and stop bits)
192  uint16_t byteval;
193 
194  // expected time per bit in system ticks
195  systime_t bit_time_tick;
196 
197  // the bit value of the last bit received
198  uint8_t last_bit;
199 
200  // thread waiting for byte to be read
201  thread_t *waiter;
202  } irq;
203 
204 
205  // the group being used for serial output
207  thread_t *serial_thread;
209 
211  uint16_t _esc_pwm_min;
212  uint16_t _esc_pwm_max;
213 
214  // offset of first local channel
215  uint8_t chan_offset;
216 
217  // total number of channels on FMU
219 
220  // number of active fmu channels
222 
223  static const uint8_t max_channels = 16;
224 
225  // last sent values are for all channels
227 
228  // these values are for the local channels. Non-local channels are handled by IOMCU
229  uint32_t en_mask;
230  uint16_t period[max_channels];
231  uint16_t safe_pwm[max_channels]; // pwm to use when safety is on
232  bool corked;
233  // mask of channels that are running in high speed
236 
237  // min time to trigger next pulse to prevent overlap
239 
240  // mutex for oneshot triggering
241  mutex_t trigger_mutex;
242 
243  // which output groups need triggering
245 
246  // widest pulse for oneshot triggering
248 
249  // are we using oneshot125 for the iomcu?
251 
252  // push out values to local PWM
253  void push_local(void);
254 
255  // trigger group pulses
256  void trigger_groups(void);
257 
258  // setup output frequency for a group
259  void set_freq_group(pwm_group &group);
260 
261  // safety switch state
264  uint8_t led_counter;
266 
267  // mask of channels to allow when safety on
268  uint16_t safety_mask;
269 
270  // update safety switch and LED
271  void safety_update(void);
272 
273  /*
274  DShot handling
275  */
276  const uint8_t dshot_post = 6;
277  const uint16_t dshot_bit_length = 16 + dshot_post;
278  const uint16_t dshot_buffer_length = dshot_bit_length*4*sizeof(uint32_t);
281 
282  void dma_allocate(Shared_DMA *ctx);
283  void dma_deallocate(Shared_DMA *ctx);
284  uint16_t create_dshot_packet(const uint16_t value, bool telem_request);
285  void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul);
286  void dshot_send(pwm_group &group, bool blocking);
287  static void dma_irq_callback(void *p, uint32_t flags);
288  bool mode_requires_dma(enum output_mode mode) const;
289  bool setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high);
290  void send_pulses_DMAR(pwm_group &group, uint32_t buffer_length);
291  void set_group_mode(pwm_group &group);
292 
293  // serial output support
294  static const eventmask_t serial_event_mask = EVENT_MASK(1);
295  bool serial_write_byte(uint8_t b);
296  bool serial_read_byte(uint8_t &b);
297  void fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b , uint32_t bitval);
298  static void serial_bit_irq(void);
299 
300 };
301 
302 #endif // HAL_USE_PWM
bool serial_setup_output(uint8_t chan, uint32_t baudrate) override
Definition: RCOutput.cpp:977
uint16_t _esc_pwm_min
Definition: RCOutput.h:211
void push_local(void)
Definition: RCOutput.cpp:344
void safety_update(void)
Definition: RCOutput.cpp:1335
thread_t * serial_thread
Definition: RCOutput.h:207
const uint8_t dshot_post
Definition: RCOutput.h:276
uint16_t _esc_pwm_max
Definition: RCOutput.h:212
void set_freq_group(pwm_group &group)
Definition: RCOutput.cpp:92
tprio_t serial_priority
Definition: RCOutput.h:208
bool setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high)
Definition: RCOutput.cpp:497
bool enable_px4io_sbus_out(uint16_t rate_hz) override
Definition: RCOutput.cpp:704
uint16_t read_last_sent(uint8_t ch) override
Definition: RCOutput.cpp:456
void set_telem_request_mask(uint16_t mask)
Definition: RCOutput.h:128
void fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval)
Definition: RCOutput.cpp:1041
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void force_safety_off(void) override
Definition: RCOutput.cpp:1303
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.cpp:641
void send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
Definition: RCOutput.cpp:920
void timer_tick(void) override
Definition: RCOutput.cpp:768
void set_default_rate(uint16_t rate_hz) override
Definition: RCOutput.cpp:216
void serial_end(void) override
Definition: RCOutput.cpp:1251
enum output_mode current_mode
Definition: RCOutput.h:149
static uint16_t pwm
Definition: RCOutput.cpp:20
void set_freq(uint32_t chmask, uint16_t freq_hz)
Definition: RCOutput.cpp:163
uint16_t last_sent[max_channels]
Definition: RCOutput.h:226
uint16_t trigger_widest_pulse
Definition: RCOutput.h:247
uint16_t safety_mask
Definition: RCOutput.h:268
bool serial_read_byte(uint8_t &b)
Definition: RCOutput.cpp:1165
const uint16_t dshot_bit_length
Definition: RCOutput.h:277
uint64_t min_pulse_trigger_us
Definition: RCOutput.h:238
void push(void) override
Definition: RCOutput.cpp:690
uint16_t io_fast_channel_mask
Definition: RCOutput.h:235
uint8_t chan_offset
Definition: RCOutput.h:215
uint32_t safety_update_ms
Definition: RCOutput.h:263
void cork(void) override
Definition: RCOutput.cpp:677
bool force_safety_on(void) override
Definition: RCOutput.cpp:1287
uint16_t create_dshot_packet(const uint16_t value, bool telem_request)
Definition: RCOutput.cpp:826
uint8_t led_counter
Definition: RCOutput.h:264
uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) override
Definition: RCOutput.cpp:1192
bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) override
Definition: RCOutput.h:42
void dma_allocate(Shared_DMA *ctx)
Definition: RCOutput.cpp:800
struct pwm_group * serial_group
Definition: RCOutput.h:206
static pwm_group pwm_group_list[]
Definition: RCOutput.h:210
uint16_t safe_pwm[max_channels]
Definition: RCOutput.h:231
uint32_t dshot_pulse_time_us
Definition: RCOutput.h:279
void write(uint8_t ch, uint16_t period_us)
Definition: RCOutput.cpp:301
uint8_t num_fmu_channels
Definition: RCOutput.h:218
void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
Definition: RCOutput.cpp:851
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:1318
safety_state
Definition: Util.h:35
static void serial_bit_irq(void)
Definition: RCOutput.cpp:1111
mutex_t trigger_mutex
Definition: RCOutput.h:241
bool serial_write_bytes(const uint8_t *bytes, uint16_t len) override
Definition: RCOutput.cpp:1085
static const eventmask_t serial_event_mask
Definition: RCOutput.h:294
uint8_t trigger_groupmask
Definition: RCOutput.h:244
bool iomcu_oneshot125
Definition: RCOutput.h:250
uint32_t en_mask
Definition: RCOutput.h:229
AP_HAL::Util::safety_state _safety_switch_state(void)
Definition: RCOutput.cpp:1274
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
Definition: RCOutput.h:38
void dma_deallocate(Shared_DMA *ctx)
Definition: RCOutput.cpp:813
AP_HAL::Util::safety_state safety_state
Definition: RCOutput.h:262
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void set_group_mode(pwm_group &group)
Definition: RCOutput.cpp:573
bool serial_write_byte(uint8_t b)
Definition: RCOutput.cpp:1063
float scale_esc_to_unity(uint16_t pwm) override
Definition: RCOutput.h:49
bool mode_requires_dma(enum output_mode mode) const
Definition: RCOutput.cpp:477
void trigger_groups(void)
Definition: RCOutput.cpp:717
void enable_ch(uint8_t ch)
Definition: RCOutput.cpp:260
float value
void disable_ch(uint8_t ch)
Definition: RCOutput.cpp:280
uint8_t active_fmu_channels
Definition: RCOutput.h:221
int8_t safety_button_counter
Definition: RCOutput.h:265
static struct ChibiOS::RCOutput::irq_state irq
uint16_t period[max_channels]
Definition: RCOutput.h:230
uint16_t get_freq(uint8_t ch)
Definition: RCOutput.cpp:236
bool setup_serial_output(uint16_t chan_mask, ByteBuffer *buffer, uint32_t baudrate)
void dshot_send(pwm_group &group, bool blocking)
Definition: RCOutput.cpp:866
static void dma_irq_callback(void *p, uint32_t flags)
Definition: RCOutput.cpp:954
const stm32_dma_stream_t * dma
Definition: RCOutput.h:152
uint16_t telem_request_mask
Definition: RCOutput.h:280
static const uint8_t max_channels
Definition: RCOutput.h:223
const uint16_t dshot_buffer_length
Definition: RCOutput.h:278
struct ChibiOS::RCOutput::pwm_group::@40 serial
uint16_t fast_channel_mask
Definition: RCOutput.h:234
uint16_t read(uint8_t ch)
Definition: RCOutput.cpp:423