PX4 Firmware
PX4 Autopilot Software http://px4.io
ADIS16448.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018-2019 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 adis16448.cpp
36  *
37  * Driver for the Analog device ADIS16448 connected via SPI.
38  *
39  * @author Amir Melzer
40  * @author Andrew Tridgell
41  * @author Pat Hickey
42  * @author Lorenz Meier <lm@inf.ethz.ch>
43  */
44 
45 #include <drivers/device/spi.h>
46 #include <ecl/geo/geo.h>
52 #include <perf/perf_counter.h>
53 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
54 
55 using namespace time_literals;
56 
57 #define DIR_READ 0x00
58 #define DIR_WRITE 0x80
59 
60 #define ADIS16448_GPIO_CTRL 0x32 /* Auxiliary digital input/output control */
61 #define ADIS16448_MSC_CTRL 0x34 /* Miscellaneous control */
62 #define ADIS16448_SMPL_PRD 0x36 /* Internal sample period (rate) control */
63 #define ADIS16448_SENS_AVG 0x38 /* Dynamic range and digital filter control */
64 #define ADIS16448_DIAG_STAT 0x3C /* System status */
65 #define ADIS16448_GLOB_CMD 0x3E /* System command */
66 #define ADIS16448_PRODUCT_ID 0x56 /* Product identifier */
67 #define ADIS16334_SERIAL_NUMBER 0x58 /* Serial number, lot specific */
68 
69 #define ADIS16448_Product 0x4040/* Product ID Description for ADIS16448 */
70 
71 #define BITS_SMPL_PRD_NO_TAP_CFG (0<<8)
72 #define BITS_SMPL_PRD_2_TAP_CFG (1<<8)
73 #define BITS_SMPL_PRD_4_TAP_CFG (2<<8)
74 #define BITS_SMPL_PRD_8_TAP_CFG (3<<8)
75 #define BITS_SMPL_PRD_16_TAP_CFG (4<<8)
76 
77 #define BITS_GYRO_DYN_RANGE_1000_CFG (4<<8)
78 #define BITS_GYRO_DYN_RANGE_500_CFG (2<<8)
79 #define BITS_GYRO_DYN_RANGE_250_CFG (1<<8)
80 
81 #define BITS_FIR_NO_TAP_CFG (0<<0)
82 #define BITS_FIR_2_TAP_CFG (1<<0)
83 #define BITS_FIR_4_TAP_CFG (2<<0)
84 #define BITS_FIR_8_TAP_CFG (3<<0)
85 #define BITS_FIR_16_TAP_CFG (4<<0)
86 #define BITS_FIR_32_TAP_CFG (5<<0)
87 #define BITS_FIR_64_TAP_CFG (6<<0)
88 #define BITS_FIR_128_TAP_CFG (7<<0)
89 
90 #define T_STALL 9
91 
92 static constexpr float ADIS16448_ACCEL_SENSITIVITY{1.0f / 1200.0f * CONSTANTS_ONE_G}; // 1200 LSB/g
93 static constexpr float ADIS16448_GYRO_INITIAL_SENSITIVITY{math::radians(1.0 / 25.0)}; // 25 LSB/°/sec
94 static constexpr float ADIS16448_BARO_SENSITIVITY{0.02f}; // 20 microbar per LSB,
95 static constexpr float ADIS16448_MAG_SENSITIVITY{1.0 / 7.0 / 1000.0}; // 7 LSB/mgauss
96 
97 
98 static constexpr float ADIS16448_ACCEL_GYRO_UPDATE_RATE{819.2}; // accel and gryo max update 819.2 samples per second
99 static constexpr float ADIS16448_MAG_BARO_UPDATE_RATE{51.2}; // xMAGN_OUT and BARO_OUT registers update at 51.2 samples per second
100 
101 class ADIS16448 : public device::SPI, public px4::ScheduledWorkItem
102 {
103 public:
104  ADIS16448(int bus, uint32_t device, enum Rotation rotation);
105  virtual ~ADIS16448();
106 
107  virtual int init();
108 
109  /**
110  * Diagnostics - print some basic information about the driver and sensor.
111  */
112  void print_info();
113 
114 protected:
115  virtual int probe();
116 
117 private:
118 
119  enum class
120  Register : uint8_t {
121  GPIO_CTRL = 0x32, // Auxiliary digital input/output control
122  MSC_CTRL = 0x34, // Miscellaneous control
123  SMPL_PRD = 0x36, // Internal sample period (rate) control
124  SENS_AVG = 0x38, // Dynamic range and digital filter control
125 
126  DIAG_STAT = 0x3C, // System status
127  GLOB_CMD = 0x3E, // System command
128 
129  PRODUCT_ID = 0x56, // Product identifier
130  SERIAL_NUMBER = 0x58, // Serial number, lot specific
131  };
132 
133  /**
134  * Fetch measurements from the sensor and update the report buffers.
135  */
136  int measure();
137 
138  /**
139  * Static trampoline from the hrt_call context; because we don't have a
140  * generic hrt wrapper yet.
141  * Called by the HRT in interrupt context at the specified rate if
142  * automatic polling is enabled.
143  *
144  * @param arg Instance pointer for the driver that is polling.
145  */
146  void Run();
147 
148  /**
149  * Modify a register in the ADIS16448
150  * Bits are cleared before bits are set.
151  *
152  * @param reg The register to modify.
153  * @param clearbits Bits in the register to clear.
154  * @param setbits Bits in the register to set.
155  */
156  void modify_reg16(unsigned reg, uint16_t clearbits, uint16_t setbits);
157 
158  /**
159  * Resets the chip and measurements ranges
160  */
161  bool reset();
162 
163  bool self_test();
164 
165  /**
166  * Read a register from the ADIS16448
167  * @arg reg The register to read.
168  * @return Returns the register value.
169  */
170  uint16_t read_reg16(unsigned reg);
171 
172  /**
173  * Write a register in the ADIS16448
174  * @param reg The register to write.
175  * @param value The new value to write.
176  */
177  void write_reg16(unsigned reg, uint16_t value);
178 
179  /**
180  * Set low pass filter frequency.
181  */
182  bool set_dlpf_filter(uint16_t frequency_hz);
183 
184  /**
185  * Set the gyroscope dynamic range.
186  */
187  bool set_gyro_dyn_range(uint16_t desired_gyro_dyn_range);
188 
189  /**
190  * Set sample rate (approximate) - 1kHz to 5Hz.
191  */
192  bool set_sample_rate(uint16_t desired_sample_rate_hz);
193 
194  /**
195  * Start automatic measurement.
196  */
197  void start();
198 
199  /**
200  * Stop automatic measurement.
201  */
202  void stop();
203 
208 
209  uint16_t _product_ID{0}; // Product ID code.
210 
211  static constexpr float _sample_rate{ADIS16448_ACCEL_GYRO_UPDATE_RATE};
212 
213  perf_counter_t _perf_read{perf_counter_t(perf_alloc(PC_ELAPSED, "ADIS16448: read"))};
214  perf_counter_t _perf_transfer{perf_counter_t(perf_alloc(PC_ELAPSED, "ADIS16448: transfer"))};
215  perf_counter_t _perf_bad_transfer{perf_counter_t(perf_alloc(PC_COUNT, "ADIS16448: bad transfers"))};
216  perf_counter_t _perf_crc_bad{perf_counter_t(perf_alloc(PC_COUNT, "ADIS16448: CRC16 bad"))};
217 
218 };
static constexpr float ADIS16448_ACCEL_GYRO_UPDATE_RATE
Definition: ADIS16448.h:98
measure the time elapsed performing an event
Definition: perf_counter.h:56
static constexpr uint8_t MSC_CTRL
Definition: ADIS16477.cpp:42
Definition of geo / math functions to perform geodesic calculations.
static constexpr float ADIS16448_MAG_SENSITIVITY
Definition: ADIS16448.h:95
static constexpr float ADIS16448_BARO_SENSITIVITY
Definition: ADIS16448.h:94
PX4Accelerometer _px4_accel
Definition: ADIS16448.h:204
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static void stop()
Definition: dataman.cpp:1491
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
count the number of times an event occurs
Definition: perf_counter.h:55
Vector rotation library.
static constexpr float CONSTANTS_ONE_G
Definition: geo.h:51
static constexpr float ADIS16448_GYRO_INITIAL_SENSITIVITY
Definition: ADIS16448.h:93
Header common to all counters.
void init()
Activates/configures the hardware registers.
static constexpr uint8_t DIAG_STAT
Definition: ADIS16477.cpp:40
PX4Barometer _px4_baro
Definition: ADIS16448.h:205
#define perf_alloc(a, b)
Definition: px4io.h:59
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
static constexpr float ADIS16448_ACCEL_SENSITIVITY
Definition: ADIS16448.h:92
constexpr T radians(T degrees)
Definition: Limits.hpp:85
PX4Magnetometer _px4_mag
Definition: ADIS16448.h:207
static constexpr uint8_t GPIO_CTRL
Definition: ADIS16497.cpp:51
static constexpr uint8_t GLOB_CMD
Definition: ADIS16477.cpp:44
static int start()
Definition: dataman.cpp:1452
struct perf_ctr_header * perf_counter_t
Definition: perf_counter.h:61
static constexpr uint8_t PRODUCT_ID
static constexpr float ADIS16448_MAG_BARO_UPDATE_RATE
Definition: ADIS16448.h:99
PX4Gyroscope _px4_gyro
Definition: ADIS16448.h:206
Performance measuring tools.