Firmware
px4io_serial.h
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 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 
40 #pragma once
41 
42 /* XXX trim includes */
43 #include <px4_config.h>
44 #include <px4_posix.h>
45 
46 #include <sys/types.h>
47 #include <stdint.h>
48 #include <stdbool.h>
49 #include <assert.h>
50 #include <debug.h>
51 #include <time.h>
52 #include <errno.h>
53 #include <string.h>
54 #include <stdio.h>
55 
56 #include <arch/board/board.h>
57 #include <perf/perf_counter.h>
58 
59 #include <board_config.h>
60 
61 #include <drivers/device/device.h>
63 
65 {
66 public:
67  PX4IO_serial();
68  virtual ~PX4IO_serial();
69 
70  virtual int init() = 0;
71  virtual int read(unsigned offset, void *data, unsigned count = 1);
72  virtual int write(unsigned address, void *data, unsigned count = 1);
73 
74 protected:
80  int init(IOPacket *io_buffer);
81 
85  virtual int _bus_exchange(IOPacket *_packet) = 0;
86 
91  perf_counter_t _pc_retries;
92  perf_counter_t _pc_timeouts;
93  perf_counter_t _pc_crcerrs;
94  perf_counter_t _pc_protoerrs;
95  perf_counter_t _pc_uerrs;
96  perf_counter_t _pc_idle;
97  perf_counter_t _pc_badidle;
98 private:
99  /*
100  * XXX tune this value
101  *
102  * At 1.5Mbps each register takes 13.3µs, and we always transfer a full packet.
103  * Packet overhead is 26µs for the four-byte header.
104  *
105  * 32 registers = 451µs
106  *
107  * Maybe we can just send smaller packets (e.g. 8 regs) and loop for larger (less common)
108  * transfers? Could cause issues with any regs expecting to be written atomically...
109  */
110  IOPacket *_io_buffer_ptr;
111 
113  px4_sem_t _bus_semaphore;
114 
115  /* do not allow top copying this class */
117  PX4IO_serial &operator = (const PX4IO_serial &);
118 };
119 
120 #if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F4XXX)
121 
123 #define PX4IO_INTERFACE_CLASS PX4IO_serial_f4
124 #define PX4IO_INTERFACE_F4
125 
126 class PX4IO_serial_f4 : public PX4IO_serial
127 {
128 public:
129  PX4IO_serial_f4();
130  ~PX4IO_serial_f4();
131 
132  virtual int init();
133  virtual int ioctl(unsigned operation, unsigned &arg);
134 
135 protected:
139  int _bus_exchange(IOPacket *_packet);
140 
141 private:
142  DMA_HANDLE _tx_dma;
143  DMA_HANDLE _rx_dma;
144 
145  IOPacket *_current_packet;
146 
148  static const unsigned _dma_status_inactive = 0x80000000; // low bits overlap DMA_STATUS_* values
149  static const unsigned _dma_status_waiting = 0x00000000;
150  volatile unsigned _rx_dma_status;
151 
153  px4_sem_t _completion_semaphore;
154 
158  static void _dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
159  void _do_rx_dma_callback(unsigned status);
160 
164  static int _interrupt(int vector, void *context, void *arg);
165  void _do_interrupt();
166 
170  void _abort_dma();
171 
175  perf_counter_t _pc_dmasetup;
176  perf_counter_t _pc_dmaerrs;
177 
178  /* do not allow top copying this class */
179  PX4IO_serial_f4(PX4IO_serial_f4 &);
180  PX4IO_serial_f4 &operator = (const PX4IO_serial_f4 &);
181 
185  static IOPacket _io_buffer_storage; // XXX static to ensure DMA-able memory
186 };
187 
188 #elif defined(CONFIG_ARCH_CHIP_STM32F7)
189 
190 #define PX4IO_INTERFACE_CLASS PX4IO_serial_f7
191 #define PX4IO_INTERFACE_F7
192 
193 #include <stm32_dma.h>
194 
195 
196 class PX4IO_serial_f7 : public PX4IO_serial
197 {
198 public:
199  PX4IO_serial_f7();
200  ~PX4IO_serial_f7();
201 
202  virtual int init();
203  virtual int ioctl(unsigned operation, unsigned &arg);
204 
205 protected:
209  int _bus_exchange(IOPacket *_packet);
210 
211 private:
212  DMA_HANDLE _tx_dma;
213  DMA_HANDLE _rx_dma;
214 
215  IOPacket *_current_packet;
216 
218  static const unsigned _dma_status_inactive = 0x80000000; // low bits overlap DMA_STATUS_* values
219  static const unsigned _dma_status_waiting = 0x00000000;
220  volatile unsigned _rx_dma_status;
221 
223  px4_sem_t _completion_semaphore;
224 
228  static void _dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
229  void _do_rx_dma_callback(unsigned status);
230 
234  static int _interrupt(int vector, void *context, void *arg);
235  void _do_interrupt();
236 
240  void _abort_dma();
241 
245  perf_counter_t _pc_dmasetup;
246  perf_counter_t _pc_dmaerrs;
247 
248  /* do not allow top copying this class */
249  PX4IO_serial_f7(PX4IO_serial_f7 &);
250  PX4IO_serial_f7 &operator = (const PX4IO_serial_f7 &);
251 
255  static uint8_t _io_buffer_storage[];
256 };
257 
258 #else
259 #error "Interface not implemented for this chip"
260 #endif
virtual int write(unsigned address, void *data, unsigned count=1)
Write directly to the device.
Definition: px4io_serial.cpp:108
perf_counter_t _pc_txns
Performance counters.
Definition: px4io_serial.h:90
virtual int ioctl(unsigned operation, unsigned &arg)
Perform a device-specific operation.
Definition: Device.hpp:117
virtual int init()=0
Initialise the driver and make it ready for use.
Configuration flags used in code.
Includes POSIX-like functions for virtual character devices.
PX4IO interface protocol.
virtual int _bus_exchange(IOPacket *_packet)=0
Start the transaction with IO and wait for it to complete.
Header common to all counters.
Definition: perf_counter.cpp:65
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
Definition: protocol.h:328
virtual int read(unsigned offset, void *data, unsigned count=1)
Read directly from the device.
Definition: px4io_serial.cpp:165
Definition: px4io_serial.h:64
Performance measuring tools.