PX4 Firmware
PX4 Autopilot Software http://px4.io
lps25h_spi.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 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 LPS25H_SPI.cpp
36  *
37  * SPI interface for LPS25H
38  */
39 
40 #include "lps25h.h"
41 
42 #ifdef PX4_SPIDEV_HMC
43 
44 /* SPI protocol address bits */
45 #define DIR_READ (1<<7)
46 #define DIR_WRITE (0<<7)
47 
48 #define HMC_MAX_SEND_LEN 4
49 #define HMC_MAX_RCV_LEN 8
50 
52 
53 class LPS25H_SPI : public device::SPI
54 {
55 public:
56  LPS25H_SPI(int bus, uint32_t device);
57  virtual ~LPS25H_SPI() = default;
58 
59  virtual int init();
60  virtual int read(unsigned address, void *data, unsigned count);
61  virtual int write(unsigned address, void *data, unsigned count);
62 
63  virtual int ioctl(unsigned operation, unsigned &arg);
64 
65 };
66 
68 LPS25H_SPI_interface(int bus)
69 {
70  return new LPS25H_SPI(bus, PX4_SPIDEV_HMC);
71 }
72 
73 LPS25H_SPI::LPS25H_SPI(int bus, uint32_t device) :
74  SPI("LPS25H_SPI", nullptr, bus, device, SPIDEV_MODE3, 11 * 1000 * 1000 /* will be rounded to 10.4 MHz */)
75 {
76  _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LPS25H;
77 }
78 
79 int
81 {
82  int ret;
83 
84  ret = SPI::init();
85 
86  if (ret != OK) {
87  DEVICE_DEBUG("SPI init failed");
88  return -EIO;
89  }
90 
91  // read WHO_AM_I value
92  uint8_t id;
93 
94  if (read(ADDR_ID, &id, 1)) {
95  DEVICE_DEBUG("read_reg fail");
96  return -EIO;
97  }
98 
99  if (id != ID_WHO_AM_I) {
100  DEVICE_DEBUG("ID byte mismatch (%02x != %02x)", ID_WHO_AM_I, id);
101  return -EIO;
102  }
103 
104  return OK;
105 }
106 
107 int
108 LPS25H_SPI::ioctl(unsigned operation, unsigned &arg)
109 {
110  int ret;
111 
112  switch (operation) {
113 
114  case DEVIOCGDEVICEID:
115  return CDev::ioctl(nullptr, operation, arg);
116 
117  default: {
118  ret = -EINVAL;
119  }
120  }
121 
122  return ret;
123 }
124 
125 int
126 LPS25H_SPI::write(unsigned address, void *data, unsigned count)
127 {
128  uint8_t buf[32];
129 
130  if (sizeof(buf) < (count + 1)) {
131  return -EIO;
132  }
133 
134  buf[0] = address | DIR_WRITE;
135  memcpy(&buf[1], data, count);
136 
137  return transfer(&buf[0], &buf[0], count + 1);
138 }
139 
140 int
141 LPS25H_SPI::read(unsigned address, void *data, unsigned count)
142 {
143  uint8_t buf[32];
144 
145  if (sizeof(buf) < (count + 1)) {
146  return -EIO;
147  }
148 
149  buf[0] = address | DIR_READ;
150 
151  int ret = transfer(&buf[0], &buf[0], count + 1);
152  memcpy(data, &buf[1], count);
153  return ret;
154 }
155 
156 #endif /* PX4_SPIDEV_HMC */
Shared defines for the lps25h driver.
device::Device * LPS25H_SPI_interface(int bus)
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
#define DIR_READ
Definition: bmp388_spi.cpp:46
static void read(bootloader_app_shared_t *pshared)
#define ID_WHO_AM_I
Definition: lps25h.h:59
void init()
Activates/configures the hardware registers.
virtual int read(unsigned address, void *data, unsigned count)
Definition: lps25h_i2c.cpp:128
uint8_t * data
Definition: dataman.cpp:149
#define DIR_WRITE
Definition: bmp388_spi.cpp:47
static void write(bootloader_app_shared_t *pshared)
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
#define OK
Definition: uavcan_main.cpp:71
#define DEVICE_DEBUG(FMT,...)
Definition: Device.hpp:52