PX4 Firmware
PX4 Autopilot Software http://px4.io
serial.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file serial.c
36  *
37  * Serial communication for the PX4IO module.
38  */
39 
40 #include <stdint.h>
41 #include <unistd.h>
42 #include <termios.h>
43 #include <fcntl.h>
44 #include <string.h>
45 
46 #include <nuttx/arch.h>
47 #include <arch/board/board.h>
48 
49 /* XXX might be able to prune these */
50 #include <chip.h>
51 #include <up_internal.h>
52 #include <up_arch.h>
53 #include <stm32.h>
54 #include <perf/perf_counter.h>
55 
56 //#define DEBUG
57 #include "px4io.h"
58 
68 
69 static void rx_handle_packet(void);
70 static void rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
71 static DMA_HANDLE tx_dma;
72 static DMA_HANDLE rx_dma;
73 
74 static int serial_interrupt(int irq, void *context, FAR void *arg);
75 static void dma_reset(void);
76 
77 static struct IOPacket dma_packet;
78 
79 /* serial register accessors */
80 #define REG(_x) (*(volatile uint32_t *)(PX4FMU_SERIAL_BASE + _x))
81 #define rSR REG(STM32_USART_SR_OFFSET)
82 #define rDR REG(STM32_USART_DR_OFFSET)
83 #define rBRR REG(STM32_USART_BRR_OFFSET)
84 #define rCR1 REG(STM32_USART_CR1_OFFSET)
85 #define rCR2 REG(STM32_USART_CR2_OFFSET)
86 #define rCR3 REG(STM32_USART_CR3_OFFSET)
87 #define rGTPR REG(STM32_USART_GTPR_OFFSET)
88 
89 void
91 {
92  pc_txns = perf_alloc(PC_ELAPSED, "txns");
93  pc_errors = perf_alloc(PC_COUNT, "errors");
94  pc_ore = perf_alloc(PC_COUNT, "overrun");
95  pc_fe = perf_alloc(PC_COUNT, "framing");
96  pc_ne = perf_alloc(PC_COUNT, "noise");
97  pc_idle = perf_alloc(PC_COUNT, "idle");
98  pc_badidle = perf_alloc(PC_COUNT, "badidle");
99  pc_regerr = perf_alloc(PC_COUNT, "regerr");
100  pc_crcerr = perf_alloc(PC_COUNT, "crcerr");
101 
102  /* allocate DMA */
103  tx_dma = stm32_dmachannel(PX4FMU_SERIAL_TX_DMA);
104  rx_dma = stm32_dmachannel(PX4FMU_SERIAL_RX_DMA);
105 
106  /* configure pins for serial use */
107  px4_arch_configgpio(PX4FMU_SERIAL_TX_GPIO);
108  px4_arch_configgpio(PX4FMU_SERIAL_RX_GPIO);
109 
110  /* reset and configure the UART */
111  rCR1 = 0;
112  rCR2 = 0;
113  rCR3 = 0;
114 
115  /* clear status/errors */
116  (void)rSR;
117  (void)rDR;
118 
119  /* configure line speed */
120  uint32_t usartdiv32 = PX4FMU_SERIAL_CLOCK / (PX4FMU_SERIAL_BITRATE / 2);
121  uint32_t mantissa = usartdiv32 >> 5;
122  uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
123  rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
124 
125  /* connect our interrupt */
126  irq_attach(PX4FMU_SERIAL_VECTOR, serial_interrupt, NULL);
127  up_enable_irq(PX4FMU_SERIAL_VECTOR);
128 
129  /* enable UART and error/idle interrupts */
130  rCR3 = USART_CR3_EIE;
131  rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
132 
133 #if 0 /* keep this for signal integrity testing */
134 
135  for (;;) {
136  while (!(rSR & USART_SR_TXE))
137  ;
138 
139  rDR = 0xfa;
140 
141  while (!(rSR & USART_SR_TXE))
142  ;
143 
144  rDR = 0xa0;
145  }
146 
147 #endif
148 
149  /* configure RX DMA and return to listening state */
150  dma_reset();
151 
152  debug("serial init");
153 }
154 
155 static void
157 {
158  /* check packet CRC */
159  uint8_t crc = dma_packet.crc;
160  dma_packet.crc = 0;
161 
162  if (crc != crc_packet(&dma_packet)) {
163  perf_count(pc_crcerr);
164 
165  /* send a CRC error reply */
167  dma_packet.page = 0xff;
168  dma_packet.offset = 0xff;
169 
170  return;
171  }
172 
174 
175  /* it's a blind write - pass it on */
177  perf_count(pc_regerr);
179 
180  } else {
182  }
183 
184  return;
185  }
186 
188 
189  /* it's a read - get register pointer for reply */
190  unsigned count;
191  uint16_t *registers;
192 
193  if (registers_get(dma_packet.page, dma_packet.offset, &registers, &count) < 0) {
194  perf_count(pc_regerr);
196 
197  } else {
198  /* constrain reply to requested size */
199  if (count > PKT_MAX_REGS) {
200  count = PKT_MAX_REGS;
201  }
202 
203  if (count > PKT_COUNT(dma_packet)) {
204  count = PKT_COUNT(dma_packet);
205  }
206 
207  /* copy reply registers into DMA buffer */
208  memcpy((void *)&dma_packet.regs[0], registers, count * 2);
210  }
211 
212  return;
213  }
214 
215  /* send a bad-packet error reply */
217  dma_packet.page = 0xff;
218  dma_packet.offset = 0xfe;
219 }
220 
221 static void
222 rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
223 {
224  /*
225  * We are here because DMA completed, or UART reception stopped and
226  * we think we have a packet in the buffer.
227  */
228  perf_begin(pc_txns);
229 
230  /* disable UART DMA */
231  rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
232 
233  /* handle the received packet */
235 
236  /* re-set DMA for reception first, so we are ready to receive before we start sending */
237  dma_reset();
238 
239  /* send the reply to the just-processed request */
240  dma_packet.crc = 0;
242  stm32_dmasetup(
243  tx_dma,
244  (uint32_t)&rDR,
245  (uint32_t)&dma_packet,
246  PKT_SIZE(dma_packet),
247  DMA_CCR_DIR |
248  DMA_CCR_MINC |
249  DMA_CCR_PSIZE_8BITS |
250  DMA_CCR_MSIZE_8BITS);
251  stm32_dmastart(tx_dma, NULL, NULL, false);
252  rCR3 |= USART_CR3_DMAT;
253 
254  perf_end(pc_txns);
255 }
256 
257 static int
258 serial_interrupt(int irq, void *context, FAR void *arg)
259 {
260  static bool abort_on_idle = false;
261 
262  uint32_t sr = rSR; /* get UART status register */
263  (void)rDR; /* required to clear any of the interrupt status that brought us here */
264 
265  if (sr & (USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
266  USART_SR_NE | /* noise error - we have lost a byte due to noise */
267  USART_SR_FE)) { /* framing error - start/stop bit lost or line break */
268 
269  perf_count(pc_errors);
270 
271  if (sr & USART_SR_ORE) {
272  perf_count(pc_ore);
273  }
274 
275  if (sr & USART_SR_NE) {
276  perf_count(pc_ne);
277  }
278 
279  if (sr & USART_SR_FE) {
280  perf_count(pc_fe);
281  }
282 
283  /* send a line break - this will abort transmission/reception on the other end */
284  rCR1 |= USART_CR1_SBK;
285 
286  /* when the line goes idle, abort rather than look at the packet */
287  abort_on_idle = true;
288  }
289 
290  if (sr & USART_SR_IDLE) {
291 
292  /*
293  * If we saw an error, don't bother looking at the packet - it should have
294  * been aborted by the sender and will definitely be bad. Get the DMA reconfigured
295  * ready for their retry.
296  */
297  if (abort_on_idle) {
298 
299  abort_on_idle = false;
300  dma_reset();
301  return 0;
302  }
303 
304  /*
305  * The sender has stopped sending - this is probably the end of a packet.
306  * Check the received length against the length in the header to see if
307  * we have something that looks like a packet.
308  */
309  unsigned length = sizeof(dma_packet) - stm32_dmaresidual(rx_dma);
310 
311  if ((length < 1) || (length < PKT_SIZE(dma_packet))) {
312 
313  /* it was too short - possibly truncated */
314  perf_count(pc_badidle);
315  dma_reset();
316  return 0;
317  }
318 
319  /*
320  * Looks like we received a packet. Stop the DMA and go process the
321  * packet.
322  */
323  perf_count(pc_idle);
324  stm32_dmastop(rx_dma);
325  rx_dma_callback(rx_dma, DMA_STATUS_TCIF, NULL);
326  }
327 
328  return 0;
329 }
330 
331 static void
333 {
334  rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
335  (void)rSR;
336  (void)rDR;
337  (void)rDR;
338 
339  /* kill any pending DMA */
340  stm32_dmastop(tx_dma);
341  stm32_dmastop(rx_dma);
342 
343  /* reset the RX side */
344  stm32_dmasetup(
345  rx_dma,
346  (uint32_t)&rDR,
347  (uint32_t)&dma_packet,
348  sizeof(dma_packet),
349  DMA_CCR_MINC |
350  DMA_CCR_PSIZE_8BITS |
351  DMA_CCR_MSIZE_8BITS |
352  DMA_CCR_PRIVERYHI);
353 
354  /* start receive DMA ready for the next packet */
355  stm32_dmastart(rx_dma, rx_dma_callback, NULL, false);
356  rCR3 |= USART_CR3_DMAR;
357 }
358 
static struct IOPacket dma_packet
Definition: serial.c:77
uint8_t crc
Definition: protocol.h:333
static struct vehicle_status_s status
Definition: Commander.cpp:138
measure the time elapsed performing an event
Definition: perf_counter.h:56
#define rCR3
Definition: serial.c:86
static int serial_interrupt(int irq, void *context, FAR void *arg)
Definition: serial.c:258
#define debug(fmt, args...)
static perf_counter_t pc_ne
Definition: serial.c:63
static perf_counter_t pc_badidle
Definition: serial.c:65
static perf_counter_t pc_fe
Definition: serial.c:62
count the number of times an event occurs
Definition: perf_counter.h:55
static perf_counter_t pc_ore
Definition: serial.c:61
static perf_counter_t pc_regerr
Definition: serial.c:66
uint8_t page
Definition: protocol.h:334
static perf_counter_t pc_txns
Definition: serial.c:59
#define PKT_CODE_ERROR
Definition: protocol.h:348
#define rCR2
Definition: serial.c:85
void interface_init(void)
FMU communications.
Definition: serial.c:90
static perf_counter_t pc_idle
Definition: serial.c:64
void perf_count(perf_counter_t handle)
Count a performance event.
#define PKT_CODE(_p)
Definition: protocol.h:354
Header common to all counters.
static void rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
Definition: serial.c:222
#define PKT_COUNT(_p)
Definition: protocol.h:353
static DMA_HANDLE tx_dma
Definition: serial.c:71
void * arg
Definition: drv_hrt.h:78
static void rx_handle_packet(void)
Definition: serial.c:156
#define perf_alloc(a, b)
Definition: px4io.h:59
static uint8_t crc_packet(struct IOPacket *pkt) __attribute__((unused))
Definition: protocol.h:394
int registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values)
Definition: registers.c:844
uint16_t regs[PKT_MAX_REGS]
Definition: protocol.h:336
#define rSR
Definition: serial.c:81
#define PKT_CODE_READ
Definition: protocol.h:344
uint8_t offset
Definition: protocol.h:335
#define rDR
Definition: serial.c:82
void perf_end(perf_counter_t handle)
End a performance event.
#define PKT_MAX_REGS
Serial protocol encapsulation.
Definition: protocol.h:328
static perf_counter_t pc_crcerr
Definition: serial.c:67
General defines and structures for the PX4IO module firmware.
#define PKT_CODE_CORRUPT
Definition: protocol.h:347
static DMA_HANDLE rx_dma
Definition: serial.c:72
#define rBRR
Definition: serial.c:83
#define PKT_CODE_SUCCESS
Definition: protocol.h:346
#define PKT_CODE_WRITE
Definition: protocol.h:345
uint8_t count_code
Definition: protocol.h:332
#define PKT_SIZE(_p)
Definition: protocol.h:355
int registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
Register space.
Definition: registers.c:275
void perf_begin(perf_counter_t handle)
Begin a performance event.
static perf_counter_t pc_errors
Definition: serial.c:60
static void dma_reset(void)
Definition: serial.c:332
#define rCR1
Definition: serial.c:84
Performance measuring tools.