OP-1516 fixed boundf mistake
[librepilot.git] / flight / pios / common / pios_adxl345.c
blobcb83669ec8ce6060adce4fb64554cc1525819c3a
1 /**
2 ******************************************************************************
3 * @addtogroup PIOS PIOS Core hardware abstraction layer
4 * @{
5 * @addtogroup PIOS_ADXL345 ADXL345 Functions
6 * @brief Deals with the hardware interface to the BMA180 3-axis accelerometer
7 * @{
9 * @file pios_adxl345.h
10 * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
11 * @brief PiOS ADXL345 digital accelerometer driver.
12 * @see The GNU Public License (GPL) Version 3
14 *****************************************************************************/
16 * This program is free software; you can redistribute it and/or modify
17 * it under the terms of the GNU General Public License as published by
18 * the Free Software Foundation; either version 3 of the License, or
19 * (at your option) any later version.
21 * This program is distributed in the hope that it will be useful, but
22 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
23 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
24 * for more details.
26 * You should have received a copy of the GNU General Public License along
27 * with this program; if not, write to the Free Software Foundation, Inc.,
28 * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
31 #include "pios.h"
33 #ifdef PIOS_INCLUDE_ADXL345
35 enum pios_adxl345_dev_magic {
36 PIOS_ADXL345_DEV_MAGIC = 0xcb55aa55,
39 struct adxl345_dev {
40 uint32_t spi_id;
41 uint32_t slave_num;
42 enum pios_adxl345_dev_magic magic;
45 // ! Global structure for this device device
46 static struct adxl345_dev *dev;
48 // ! Private functions
49 static struct adxl345_dev *PIOS_ADXL345_alloc(void);
50 static int32_t PIOS_ADXL345_Validate(struct adxl345_dev *dev);
51 static int32_t PIOS_ADXL345_ClaimBus();
52 static int32_t PIOS_ADXL345_ReleaseBus();
53 static int32_t PIOS_ADXL345_FifoDepth(uint8_t depth);
55 /**
56 * @brief Allocate a new device
58 static struct adxl345_dev *PIOS_ADXL345_alloc(void)
60 struct adxl345_dev *adxl345_dev;
62 adxl345_dev = (struct adxl345_dev *)pios_malloc(sizeof(*adxl345_dev));
63 if (!adxl345_dev) {
64 return NULL;
67 adxl345_dev->magic = PIOS_ADXL345_DEV_MAGIC;
68 return adxl345_dev;
71 /**
72 * @brief Validate the handle to the spi device
73 * @returns 0 for valid device or -1 otherwise
75 static int32_t PIOS_ADXL345_Validate(struct adxl345_dev *vdev)
77 if (vdev == NULL) {
78 return -1;
80 if (vdev->magic != PIOS_ADXL345_DEV_MAGIC) {
81 return -2;
83 if (vdev->spi_id == 0) {
84 return -3;
86 return 0;
89 /**
90 * @brief Claim the SPI bus for the accel communications and select this chip
91 * @return 0 for succesful claiming of bus or -1 otherwise
93 static int32_t PIOS_ADXL345_ClaimBus()
95 if (PIOS_ADXL345_Validate(dev) != 0) {
96 return -1;
99 if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
100 return -2;
103 PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
105 return 0;
109 * @brief Release the SPI bus for the accel communications and end the transaction
110 * @return 0 if success or <0 for failure
112 static int32_t PIOS_ADXL345_ReleaseBus()
114 if (PIOS_ADXL345_Validate(dev) != 0) {
115 return -1;
118 PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
120 if (PIOS_SPI_ReleaseBus(dev->spi_id) != 0) {
121 return -2;
124 return 0;
128 * @brief Select the sampling rate of the chip
130 * This also puts it into high power mode
132 int32_t PIOS_ADXL345_SelectRate(uint8_t rate)
134 if (PIOS_ADXL345_Validate(dev) != 0) {
135 return -1;
138 if (PIOS_ADXL345_ClaimBus() != 0) {
139 return -2;
142 uint8_t out[2] = { ADXL_RATE_ADDR, rate & 0x0F };
143 if (PIOS_SPI_TransferBlock(dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
144 PIOS_ADXL345_ReleaseBus();
145 return -3;
148 PIOS_ADXL345_ReleaseBus();
150 return 0;
154 * @brief Set the range of the accelerometer and set the data to be right justified
155 * with sign extension. Also keep device in 4 wire mode.
157 int32_t PIOS_ADXL345_SetRange(uint8_t range)
159 if (PIOS_ADXL345_Validate(dev) != 0) {
160 return -1;
163 if (PIOS_ADXL345_ClaimBus() != 0) {
164 return -2;
167 uint8_t out[2] = { ADXL_FORMAT_ADDR, (range & 0x03) | ADXL_FULL_RES | ADXL_4WIRE };
168 if (PIOS_SPI_TransferBlock(dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
169 PIOS_ADXL345_ReleaseBus();
170 return -3;
173 PIOS_ADXL345_ReleaseBus();
175 return 0;
179 * @brief Set the fifo depth that triggers an interrupt. This will be matched to the oversampling
181 static int32_t PIOS_ADXL345_FifoDepth(uint8_t depth)
183 if (PIOS_ADXL345_Validate(dev) != 0) {
184 return -1;
187 if (PIOS_ADXL345_ClaimBus() != 0) {
188 return -2;
191 uint8_t out[2] = { ADXL_FIFO_ADDR, (depth & 0x1f) | ADXL_FIFO_STREAM };
192 if (PIOS_SPI_TransferBlock(dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
193 PIOS_ADXL345_ReleaseBus();
194 return -3;
197 PIOS_ADXL345_ReleaseBus();
199 return 0;
203 * @brief Enable measuring. This also disables the activity sensors (tap or free fall)
205 static int32_t PIOS_ADXL345_SetMeasure(__attribute__((unused)) uint8_t enable)
207 if (PIOS_ADXL345_Validate(dev) != 0) {
208 return -1;
211 if (PIOS_ADXL345_ClaimBus() != 0) {
212 return -2;
215 uint8_t out[2] = { ADXL_POWER_ADDR, ADXL_MEAURE };
216 if (PIOS_SPI_TransferBlock(dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
217 PIOS_ADXL345_ReleaseBus();
218 return -3;
221 PIOS_ADXL345_ReleaseBus();
223 return 0;
227 * @brief Initialize with good default settings
229 int32_t PIOS_ADXL345_Init(uint32_t spi_id, uint32_t slave_num)
231 dev = PIOS_ADXL345_alloc();
232 if (dev == NULL) {
233 return -1;
236 dev->spi_id = spi_id;
237 dev->slave_num = slave_num;
239 PIOS_ADXL345_ReleaseBus();
240 PIOS_ADXL345_SelectRate(ADXL_RATE_1600);
241 PIOS_ADXL345_SetRange(ADXL_RANGE_8G);
242 PIOS_ADXL345_FifoDepth(16);
243 PIOS_ADXL345_SetMeasure(1);
245 return 0;
249 * @brief Return number of entries in the fifo
251 int32_t PIOS_ADXL345_Test()
253 if (PIOS_ADXL345_Validate(dev) != 0) {
254 return -1;
257 if (PIOS_ADXL345_ClaimBus() != 0) {
258 return -2;
261 uint8_t buf[2] = { 0, 0 };
262 uint8_t rec[2] = { 0, 0 };
263 buf[0] = ADXL_WHOAMI | ADXL_READ_BIT;
265 if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
266 PIOS_ADXL345_ReleaseBus();
267 return -3;
270 PIOS_ADXL345_ReleaseBus();
272 return (rec[1] == ADXL_DEVICE_ID) ? 0 : -4;
276 * @brief Return number of entries in the fifo
278 int32_t PIOS_ADXL345_FifoElements()
280 if (PIOS_ADXL345_Validate(dev) != 0) {
281 return -1;
284 if (PIOS_ADXL345_ClaimBus() != 0) {
285 return -2;
288 uint8_t buf[2] = { 0, 0 };
289 uint8_t rec[2] = { 0, 0 };
290 buf[0] = ADXL_FIFOSTATUS_ADDR | ADXL_READ_BIT; // Read fifo status
292 if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
293 PIOS_ADXL345_ReleaseBus();
294 return -3;
297 PIOS_ADXL345_ReleaseBus();
299 return rec[1] & 0x3f;
304 * @brief Read a single set of values from the x y z channels
305 * @returns The number of samples remaining in the fifo
307 uint8_t PIOS_ADXL345_Read(struct pios_adxl345_data *data)
309 if (PIOS_ADXL345_Validate(dev) != 0) {
310 return -1;
313 if (PIOS_ADXL345_ClaimBus() != 0) {
314 return -2;
316 // To save memory use same buffer for in and out but offset by
317 // a byte
318 uint8_t buf[10] = { 0 };
319 uint8_t *rec = buf + 1;
320 buf[0] = ADXL_X0_ADDR | ADXL_MULTI_BIT | ADXL_READ_BIT; // Multibyte read starting at X0
321 if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], 9, NULL) < 0) {
322 PIOS_ADXL345_ReleaseBus();
323 return -3;
326 PIOS_ADXL345_ReleaseBus();
328 data->x = rec[1] + (rec[2] << 8);
329 data->y = rec[3] + (rec[4] << 8);
330 data->z = rec[5] + (rec[6] << 8);
332 return rec[8] & 0x7F; // return number of remaining entries
336 * @brief Read a single set of values from the x y z channels
337 * @returns 0 if successful
340 int8_t PIOS_ADXL345_ReadAndAccumulateSamples(struct pios_adxl345_data *data, uint8_t samples)
342 if (PIOS_ADXL345_Validate(dev) != 0) {
343 return -1;
346 if (PIOS_ADXL345_ClaimBus() != 0) {
347 return -2;
349 data->x = 0;
350 data->y = 0;
351 data->z = 0;
352 // To save memory use same buffer for in and out but offset by
353 // a byte
354 #ifdef PIOS_INCLUDE_INSTRUMENTATION
355 PIOS_Instrumentation_TimeStart(counterUpd);
356 #endif
357 for (uint8_t i = 0; i < samples; i++) {
358 uint8_t buf[7] = { 0 };
359 uint8_t *rec = &buf[1];
360 PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
361 buf[0] = ADXL_X0_ADDR | ADXL_MULTI_BIT | ADXL_READ_BIT; // Multibyte read starting at X0
362 if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], 7, NULL) < 0) {
363 PIOS_ADXL345_ReleaseBus();
364 return -3;
366 PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
367 data->x += rec[1] + (rec[2] << 8);
368 data->y += rec[3] + (rec[4] << 8);
369 data->z += rec[5] + (rec[6] << 8);
371 uint8_t r = PIOS_SPI_TransferByte(dev->spi_id, ADXL_FIFOSTATUS_ADDR | ADXL_READ_BIT);
372 #ifdef PIOS_INCLUDE_INSTRUMENTATION
373 PIOS_Instrumentation_TimeEnd(counterUpd);
374 #endif
375 PIOS_ADXL345_ReleaseBus();
376 return r & 0x7F; // return number of remaining entries
378 #endif /* PIOS_INCLUDE_ADXL345 */