PX4 Firmware
PX4 Autopilot Software http://px4.io
ms5611_spi.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 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 ms5611_spi.cpp
36  *
37  * SPI interface for MS5611
38  */
39 
40 #include "ms5611.h"
41 
42 /* SPI protocol address bits */
43 #define DIR_READ (1<<7)
44 #define DIR_WRITE (0<<7)
45 #define ADDR_INCREMENT (1<<6)
46 
47 #if defined(PX4_SPIDEV_BARO) || defined(PX4_SPIDEV_EXT_BARO)
48 
49 device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus);
50 
51 class MS5611_SPI : public device::SPI
52 {
53 public:
54  MS5611_SPI(uint8_t bus, uint32_t device, ms5611::prom_u &prom_buf);
55  virtual ~MS5611_SPI() = default;
56 
57  virtual int init();
58  virtual int read(unsigned offset, void *data, unsigned count);
59  virtual int ioctl(unsigned operation, unsigned &arg);
60 
61 private:
62  ms5611::prom_u &_prom;
63 
64  /**
65  * Send a reset command to the MS5611.
66  *
67  * This is required after any bus reset.
68  */
69  int _reset();
70 
71  /**
72  * Send a measure command to the MS5611.
73  *
74  * @param addr Which address to use for the measure operation.
75  */
76  int _measure(unsigned addr);
77 
78  /**
79  * Read the MS5611 PROM
80  *
81  * @return OK if the PROM reads successfully.
82  */
83  int _read_prom();
84 
85  /**
86  * Read a 16-bit register value.
87  *
88  * @param reg The register to read.
89  */
90  uint16_t _reg16(unsigned reg);
91 
92  /**
93  * Wrapper around transfer() that prevents interrupt-context transfers
94  * from pre-empting us. The sensor may (does) share a bus with sensors
95  * that are polled from interrupt context (or we may be pre-empted)
96  * so we need to guarantee that transfers complete without interruption.
97  */
98  int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
99 };
100 
102 MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
103 {
104 #ifdef PX4_SPI_BUS_EXT
105 
106  if (busnum == PX4_SPI_BUS_EXT) {
107 #ifdef PX4_SPIDEV_EXT_BARO
108  return new MS5611_SPI(busnum, PX4_SPIDEV_EXT_BARO, prom_buf);
109 #else
110  return nullptr;
111 #endif
112  }
113 
114 #endif
115  return new MS5611_SPI(busnum, PX4_SPIDEV_BARO, prom_buf);
116 }
117 
118 MS5611_SPI::MS5611_SPI(uint8_t bus, uint32_t device, ms5611::prom_u &prom_buf) :
119  SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 20 * 1000 * 1000 /* will be rounded to 10.4 MHz */),
120  _prom(prom_buf)
121 {
122 }
123 
124 int
126 {
127  int ret = SPI::init();
128 
129  if (ret != OK) {
130  PX4_DEBUG("SPI init failed");
131  goto out;
132  }
133 
134  /* send reset command */
135  ret = _reset();
136 
137  if (ret != OK) {
138  PX4_DEBUG("reset failed");
139  goto out;
140  }
141 
142  /* read PROM */
143  ret = _read_prom();
144 
145  if (ret != OK) {
146  PX4_DEBUG("prom readout failed");
147  goto out;
148  }
149 
150 out:
151  return ret;
152 }
153 
154 int
155 MS5611_SPI::read(unsigned offset, void *data, unsigned count)
156 {
157  union _cvt {
158  uint8_t b[4];
159  uint32_t w;
160  } *cvt = (_cvt *)data;
161  uint8_t buf[4] = { 0 | DIR_WRITE, 0, 0, 0 };
162 
163  /* read the most recent measurement */
164  int ret = _transfer(&buf[0], &buf[0], sizeof(buf));
165 
166  if (ret == OK) {
167  /* fetch the raw value */
168  cvt->b[0] = buf[3];
169  cvt->b[1] = buf[2];
170  cvt->b[2] = buf[1];
171  cvt->b[3] = 0;
172 
173  ret = count;
174  }
175 
176  return ret;
177 }
178 
179 int
180 MS5611_SPI::ioctl(unsigned operation, unsigned &arg)
181 {
182  int ret;
183 
184  switch (operation) {
185  case IOCTL_RESET:
186  ret = _reset();
187  break;
188 
189  case IOCTL_MEASURE:
190  ret = _measure(arg);
191  break;
192 
193  default:
194  ret = EINVAL;
195  }
196 
197  if (ret != OK) {
198  errno = ret;
199  return -1;
200  }
201 
202  return 0;
203 }
204 
205 int
206 MS5611_SPI::_reset()
207 {
208  uint8_t cmd = ADDR_RESET_CMD | DIR_WRITE;
209 
210  return _transfer(&cmd, nullptr, 1);
211 }
212 
213 int
214 MS5611_SPI::_measure(unsigned addr)
215 {
216  uint8_t cmd = addr | DIR_WRITE;
217 
218  return _transfer(&cmd, nullptr, 1);
219 }
220 
221 
222 int
223 MS5611_SPI::_read_prom()
224 {
225  /*
226  * Wait for PROM contents to be in the device (2.8 ms) in the case we are
227  * called immediately after reset.
228  */
229  px4_usleep(3000);
230 
231  /* read and convert PROM words */
232  bool all_zero = true;
233 
234  for (int i = 0; i < 8; i++) {
235  uint8_t cmd = (ADDR_PROM_SETUP + (i * 2));
236  _prom.c[i] = _reg16(cmd);
237 
238  if (_prom.c[i] != 0) {
239  all_zero = false;
240  }
241 
242  //PX4_DEBUG("prom[%u]=0x%x", (unsigned)i, (unsigned)_prom.c[i]);
243  }
244 
245  /* calculate CRC and return success/failure accordingly */
246  int ret = ms5611::crc4(&_prom.c[0]) ? OK : -EIO;
247 
248  if (ret != OK) {
249  PX4_DEBUG("crc failed");
250  }
251 
252  if (all_zero) {
253  PX4_DEBUG("prom all zero");
254  ret = -EIO;
255  }
256 
257  return ret;
258 }
259 
260 uint16_t
261 MS5611_SPI::_reg16(unsigned reg)
262 {
263  uint8_t cmd[3] = { (uint8_t)(reg | DIR_READ), 0, 0 };
264 
265  _transfer(cmd, cmd, sizeof(cmd));
266 
267  return (uint16_t)(cmd[1] << 8) | cmd[2];
268 }
269 
270 int
271 MS5611_SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
272 {
273  return transfer(send, recv, len);
274 }
275 
276 #endif /* PX4_SPIDEV_BARO || PX4_SPIDEV_EXT_BARO */
bool crc4(uint16_t *n_prom)
MS5611 crc4 cribbed from the datasheet.
Definition: ms5611.cpp:608
#define ADDR_PROM_SETUP
Definition: ms5611.h:59
void * send(void *data)
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
static void read(bootloader_app_shared_t *pshared)
Shared defines for the ms5611 driver.
void init()
Activates/configures the hardware registers.
uint8_t * data
Definition: dataman.cpp:149
#define DIR_READ
Definition: ms5611_spi.cpp:43
#define ADDR_RESET_CMD
Definition: ms5611.h:58
#define IOCTL_MEASURE
Definition: mpl3115a2.h:93
Grody hack for crc4()
Definition: ms5611.h:86
device::Device * MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
#define OK
Definition: uavcan_main.cpp:71
#define DIR_WRITE
Definition: ms5611_spi.cpp:44
#define IOCTL_RESET
Definition: mpl3115a2.h:92