PX4 Firmware
PX4 Autopilot Software http://px4.io
bmi160.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 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 #pragma once
35 
36 #include <drivers/device/spi.h>
37 #include <ecl/geo/geo.h>
41 #include <perf/perf_counter.h>
42 #include <px4_platform_common/getopt.h>
43 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
44 #include <systemlib/conversions.h>
45 
46 #define DIR_READ 0x80
47 #define DIR_WRITE 0x00
48 
49 // BMI 160 registers
50 
51 #define BMIREG_CHIP_ID 0x00
52 #define BMIREG_ERR_REG 0x02
53 #define BMIREG_PMU_STATUS 0x03
54 #define BMIREG_DATA_0 0x04
55 #define BMIREG_DATA_1 0x05
56 #define BMIREG_DATA_2 0x06
57 #define BMIREG_DATA_3 0x07
58 #define BMIREG_DATA_4 0x08
59 #define BMIREG_DATA_5 0x09
60 #define BMIREG_DATA_6 0x0A
61 #define BMIREG_DATA_7 0x0B
62 #define BMIREG_GYR_X_L 0x0C
63 #define BMIREG_GYR_X_H 0x0D
64 #define BMIREG_GYR_Y_L 0x0E
65 #define BMIREG_GYR_Y_H 0x0F
66 #define BMIREG_GYR_Z_L 0x10
67 #define BMIREG_GYR_Z_H 0x11
68 #define BMIREG_ACC_X_L 0x12
69 #define BMIREG_ACC_X_H 0x13
70 #define BMIREG_ACC_Y_L 0x14
71 #define BMIREG_ACC_Y_H 0x15
72 #define BMIREG_ACC_Z_L 0x16
73 #define BMIREG_ACC_Z_H 0x17
74 #define BMIREG_SENSORTIME0 0x18
75 #define BMIREG_SENSORTIME1 0x19
76 #define BMIREG_SENSORTIME2 0x1A
77 #define BMIREG_STATUS 0x1B
78 #define BMIREG_INT_STATUS_0 0x1C
79 #define BMIREG_INT_STATUS_1 0x1D
80 #define BMIREG_INT_STATUS_2 0x1E
81 #define BMIREG_INT_STATUS_3 0x1F
82 #define BMIREG_TEMP_0 0x20
83 #define BMIREG_TEMP_1 0x21
84 #define BMIREG_FIFO_LEN_0 0x22
85 #define BMIREG_FIFO_LEN_1 0x23
86 #define BMIREG_FIFO_DATA 0x24
87 #define BMIREG_ACC_CONF 0x40
88 #define BMIREG_ACC_RANGE 0x41
89 #define BMIREG_GYR_CONF 0x42
90 #define BMIREG_GYR_RANGE 0x43
91 #define BMIREG_MAG_CONF 0x44
92 #define BMIREG_FIFO_DOWNS 0x45
93 #define BMIREG_FIFO_CONFIG_0 0x46
94 #define BMIREG_FIFO_CONFIG_1 0x47
95 #define BMIREG_MAG_IF_0 0x4B
96 #define BMIREG_MAG_IF_1 0x4C
97 #define BMIREG_MAG_IF_2 0x4D
98 #define BMIREG_MAG_IF_3 0x4E
99 #define BMIREG_MAG_IF_4 0x4F
100 #define BMIREG_INT_EN_0 0x50
101 #define BMIREG_INT_EN_1 0x51
102 #define BMIREG_INT_EN_2 0x52
103 #define BMIREG_INT_OUT_CTRL 0x53
104 #define BMIREG_INT_LANTCH 0x54
105 #define BMIREG_INT_MAP_0 0x55
106 #define BMIREG_INT_MAP_1 0x56
107 #define BMIREG_INT_MAP_2 0x57
108 #define BMIREG_INT_DATA_0 0x58
109 #define BMIREG_INT_DATA_1 0x59
110 #define BMIREG_INT_LH_0 0x5A
111 #define BMIREG_INT_LH_1 0x5B
112 #define BMIREG_INT_LH_2 0x5C
113 #define BMIREG_INT_LH_3 0x5D
114 #define BMIREG_INT_LH_4 0x5E
115 #define BMIREG_INT_MOT_0 0x5F
116 #define BMIREG_INT_MOT_1 0x60
117 #define BMIREG_INT_MOT_2 0x61
118 #define BMIREG_INT_MOT_3 0x62
119 #define BMIREG_INT_TAP_0 0x63
120 #define BMIREG_INT_TAP_1 0x64
121 #define BMIREG_INT_ORIE_0 0x65
122 #define BMIREG_INT_ORIE_1 0x66
123 #define BMIREG_INT_FLAT_0 0x67
124 #define BMIREG_INT_FLAT_1 0x68
125 #define BMIREG_FOC_CONF 0x69
126 #define BMIREG_CONF 0x6A
127 #define BMIREG_IF_CONF 0x6B
128 #define BMIREG_PMU_TRIGGER 0x6C
129 #define BMIREG_SELF_TEST 0x6D
130 #define BMIREG_NV_CONF 0x70
131 #define BMIREG_OFFSET_ACC_X 0x71
132 #define BMIREG_OFFSET_ACC_Y 0x72
133 #define BMIREG_OFFSET_ACC_Z 0x73
134 #define BMIREG_OFFSET_GYR_X 0x74
135 #define BMIREG_OFFSET_GYR_Y 0x75
136 #define BMIREG_OFFSET_GYR_Z 0x76
137 #define BMIREG_OFFSET_EN 0x77
138 #define BMIREG_STEP_CONT_0 0x78
139 #define BMIREG_STEP_CONT_1 0x79
140 #define BMIREG_STEP_CONF_0 0x7A
141 #define BMIREG_STEP_CONF_1 0x7B
142 #define BMIREG_CMD 0x7E
143 
144 
145 // Configuration bits BMI 160
146 #define BMI160_WHO_AM_I 0xD1
147 
148 //BMIREG_STATUS 0x1B
149 #define BMI_DRDY_ACCEL (1<<7)
150 #define BMI_DRDY_GYRO (1<<6)
151 #define BMI_DRDY_MAG (1<<5)
152 #define BMI_GYRO_SELF_TEST_OK (1<<1)
153 
154 //BMIREG_INT_STATUS_1 0x1D
155 #define BMI_DRDY_INT (1<<4)
156 
157 //BMIREG_ACC_CONF 0x40
158 #define BMI_ACCEL_RATE_25_32 (0<<3) | (0<<2) | (0<<1) | (1<<0)
159 #define BMI_ACCEL_RATE_25_16 (0<<3) | (0<<2) | (1<<1) | (0<<0)
160 #define BMI_ACCEL_RATE_25_8 (0<<3) | (0<<2) | (1<<1) | (1<<0)
161 #define BMI_ACCEL_RATE_25_4 (0<<3) | (1<<2) | (0<<1) | (0<<0)
162 #define BMI_ACCEL_RATE_25_2 (0<<3) | (1<<2) | (0<<1) | (1<<0)
163 #define BMI_ACCEL_RATE_25 (0<<3) | (1<<2) | (1<<1) | (0<<0)
164 #define BMI_ACCEL_RATE_50 (0<<3) | (1<<2) | (1<<1) | (1<<0)
165 #define BMI_ACCEL_RATE_100 (1<<3) | (0<<2) | (0<<1) | (0<<0)
166 #define BMI_ACCEL_RATE_200 (1<<3) | (0<<2) | (0<<1) | (1<<0)
167 #define BMI_ACCEL_RATE_400 (1<<3) | (0<<2) | (1<<1) | (0<<0)
168 #define BMI_ACCEL_RATE_800 (1<<3) | (0<<2) | (1<<1) | (1<<0)
169 #define BMI_ACCEL_RATE_1600 (1<<3) | (1<<2) | (0<<1) | (0<<0)
170 #define BMI_ACCEL_US (0<<7)
171 #define BMI_ACCEL_BWP_NORMAL (0<<6) | (1<<5) | (0<<4)
172 #define BMI_ACCEL_BWP_OSR2 (0<<6) | (0<<5) | (1<<4)
173 #define BMI_ACCEL_BWP_OSR4 (0<<6) | (0<<5) | (0<<4)
174 
175 //BMIREG_ACC_RANGE 0x41
176 #define BMI_ACCEL_RANGE_2_G (0<<3) | (0<<2) | (1<<1) | (1<<0)
177 #define BMI_ACCEL_RANGE_4_G (0<<3) | (1<<2) | (0<<1) | (1<<0)
178 #define BMI_ACCEL_RANGE_8_G (1<<3) | (0<<2) | (0<<1) | (0<<0)
179 #define BMI_ACCEL_RANGE_16_G (1<<3) | (1<<2) | (0<<1) | (0<<0)
180 
181 //BMIREG_GYR_CONF 0x42
182 #define BMI_GYRO_RATE_25 (0<<3) | (1<<2) | (1<<1) | (0<<0)
183 #define BMI_GYRO_RATE_50 (0<<3) | (1<<2) | (1<<1) | (1<<0)
184 #define BMI_GYRO_RATE_100 (1<<3) | (0<<2) | (0<<1) | (0<<0)
185 #define BMI_GYRO_RATE_200 (1<<3) | (0<<2) | (0<<1) | (1<<0)
186 #define BMI_GYRO_RATE_400 (1<<3) | (0<<2) | (1<<1) | (0<<0)
187 #define BMI_GYRO_RATE_800 (1<<3) | (0<<2) | (1<<1) | (1<<0)
188 #define BMI_GYRO_RATE_1600 (1<<3) | (1<<2) | (0<<1) | (0<<0)
189 #define BMI_GYRO_RATE_3200 (1<<3) | (1<<2) | (0<<1) | (1<<0)
190 #define BMI_GYRO_BWP_NORMAL (1<<5) | (0<<4)
191 #define BMI_GYRO_BWP_OSR2 (0<<5) | (1<<4)
192 #define BMI_GYRO_BWP_OSR4 (0<<5) | (0<<4)
193 
194 //BMIREG_GYR_RANGE 0x43
195 #define BMI_GYRO_RANGE_2000_DPS (0<<2) | (0<<1) | (0<<0)
196 #define BMI_GYRO_RANGE_1000_DPS (0<<2) | (0<<1) | (1<<0)
197 #define BMI_GYRO_RANGE_500_DPS (0<<2) | (1<<1) | (0<<0)
198 #define BMI_GYRO_RANGE_250_DPS (0<<2) | (1<<1) | (1<<0)
199 #define BMI_GYRO_RANGE_125_DPS (1<<2) | (0<<1) | (0<<0)
200 
201 //BMIREG_INT_EN_1 0x51
202 #define BMI_DRDY_INT_EN (1<<4)
203 
204 //BMIREG_INT_OUT_CTRL 0x53
205 #define BMI_INT1_EN (1<<3) | (0<<2) | (1<<1) //Data Ready on INT1 High
206 
207 //BMIREG_INT_MAP_1 0x56
208 #define BMI_DRDY_INT1 (1<<7)
209 
210 //BMIREG_IF_CONF 0x6B
211 #define BMI_SPI_3_WIRE (1<<0)
212 #define BMI_SPI_4_WIRE (0<<0)
213 #define BMI_AUTO_DIS_SEC (0<<5) | (0<<4)
214 #define BMI_I2C_OIS_SEC (0<<5) | (1<<4)
215 #define BMI_AUTO_MAG_SEC (1<<5) | (0<<4)
216 
217 //BMIREG_NV_CONF 0x70
218 #define BMI_SPI (1<<0)
219 
220 //BMIREG_CMD 0x7E
221 #define BMI_ACCEL_NORMAL_MODE 0x11 //Wait at least 3.8 ms before another CMD
222 #define BMI_GYRO_NORMAL_MODE 0x15 //Wait at least 80 ms before another CMD
223 #define BMI160_SOFT_RESET 0xB6
224 
225 #define BMI160_ACCEL_DEFAULT_RANGE_G 16
226 #define BMI160_GYRO_DEFAULT_RANGE_DPS 2000
227 #define BMI160_ACCEL_DEFAULT_RATE 800
228 #define BMI160_ACCEL_MAX_RATE 1600
229 #define BMI160_ACCEL_MAX_PUBLISH_RATE 280
230 #define BMI160_GYRO_DEFAULT_RATE 800
231 #define BMI160_GYRO_MAX_RATE 3200
232 #define BMI160_GYRO_MAX_PUBLISH_RATE BMI160_ACCEL_MAX_PUBLISH_RATE
233 
234 #define BMI160_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 324
235 #define BMI160_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 50
236 
237 #define BMI160_GYRO_DEFAULT_ONCHIP_FILTER_FREQ 254.6f
238 #define BMI160_GYRO_DEFAULT_DRIVER_FILTER_FREQ 50
239 
240 #define BMI160_BUS_SPEED 10*1000*1000
241 
242 #define BMI160_TIMER_REDUCTION 200
243 
244 using namespace time_literals;
245 
246 class BMI160 : public device::SPI, public px4::ScheduledWorkItem
247 {
248 public:
249  BMI160(int bus, uint32_t device, enum Rotation rotation);
250  virtual ~BMI160();
251 
252  virtual int init();
253 
254  /**
255  * Diagnostics - print some basic information about the driver.
256  */
257  void print_info();
258 
259  void print_registers();
260 
261  // deliberately cause a sensor error
262  void test_error();
263 
264 protected:
265  virtual int probe();
266 
267 private:
268 
271 
272  uint8_t _whoami; /** whoami result */
273 
274  unsigned _dlpf_freq;
275 
276  float _accel_sample_rate{BMI160_ACCEL_DEFAULT_RATE};
277  float _gyro_sample_rate{BMI160_GYRO_DEFAULT_RATE};
278 
287 
288  uint8_t _register_wait{0};
289  uint64_t _reset_wait{0};
290 
291  // this is used to support runtime checking of key
292  // configuration registers to detect SPI bus errors and sensor
293  // reset
294  static constexpr int BMI160_NUM_CHECKED_REGISTERS{10};
295  static const uint8_t _checked_registers[BMI160_NUM_CHECKED_REGISTERS];
296  uint8_t _checked_values[BMI160_NUM_CHECKED_REGISTERS];
297  uint8_t _checked_bad[BMI160_NUM_CHECKED_REGISTERS];
298  uint8_t _checked_next{0};
299 
300  // keep last accel reading for duplicate detection
301  uint16_t _last_accel[3] {};
302  bool _got_duplicate{false};
303 
304  /**
305  * Start automatic measurement.
306  */
307  void start();
308 
309  /**
310  * Stop automatic measurement.
311  */
312  void stop();
313 
314  /**
315  * Reset chip.
316  *
317  * Resets the chip and measurements ranges, but not scale and offset.
318  */
319  int reset();
320 
321  void Run() override;
322 
323  /**
324  * Fetch measurements from the sensor and update the report buffers.
325  */
326  void measure();
327 
328  /**
329  * Read a register from the BMI160
330  *
331  * @param The register to read.
332  * @return The value that was read.
333  */
334  uint8_t read_reg(unsigned reg);
335  uint16_t read_reg16(unsigned reg);
336 
337  /**
338  * Write a register in the BMI160
339  *
340  * @param reg The register to write.
341  * @param value The new value to write.
342  */
343  void write_reg(unsigned reg, uint8_t value);
344 
345  /**
346  * Modify a register in the BMI160
347  *
348  * Bits are cleared before bits are set.
349  *
350  * @param reg The register to modify.
351  * @param clearbits Bits in the register to clear.
352  * @param setbits Bits in the register to set.
353  */
354  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
355 
356  /**
357  * Write a register in the BMI160, updating _checked_values
358  *
359  * @param reg The register to write.
360  * @param value The new value to write.
361  */
362  void write_checked_reg(unsigned reg, uint8_t value);
363 
364  /**
365  * Set the BMI160 measurement range.
366  *
367  * @param max_g The maximum G value the range must support.
368  * @param max_dps The maximum DPS value the range must support.
369  * @return OK if the value can be supported, -ERANGE otherwise.
370  */
371  int set_accel_range(unsigned max_g);
372  int set_gyro_range(unsigned max_dps);
373 
374  /**
375  * Swap a 16-bit value read from the BMI160 to native byte order.
376  */
377  uint16_t swap16(uint16_t val) { return (val >> 8) | (val << 8); }
378 
379  /*
380  set low pass filter frequency
381  */
382  void _set_dlpf_filter(uint16_t frequency_hz);
383 
384  /*
385  set sample rate (approximate) - 10 - 952 Hz
386  */
387  int accel_set_sample_rate(float desired_sample_rate_hz);
388  int gyro_set_sample_rate(float desired_sample_rate_hz);
389  /*
390  check that key registers still have the right value
391  */
392  void check_registers(void);
393 
394  /* do not allow to copy this class due to pointer data members */
395  BMI160(const BMI160 &);
396  BMI160 operator=(const BMI160 &);
397 
398 #pragma pack(push, 1)
399  /**
400  * Report conversation within the BMI160, including command byte and
401  * interrupt status.
402  */
403  struct BMIReport {
404  uint8_t cmd;
405  int16_t gyro_x;
406  int16_t gyro_y;
407  int16_t gyro_z;
408  int16_t accel_x;
409  int16_t accel_y;
410  int16_t accel_z;
411  };
412 #pragma pack(pop)
413 };
Definition of geo / math functions to perform geodesic calculations.
#define BMI160_GYRO_DEFAULT_RATE
Definition: bmi160.hpp:230
int reset(enum LPS22HB_BUS busid)
Reset the driver.
PX4Gyroscope _px4_gyro
Definition: bmi160.hpp:270
static void stop()
Definition: dataman.cpp:1491
int16_t gyro_y
Definition: bmi160.hpp:406
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
Vector rotation library.
PX4Accelerometer _px4_accel
Definition: bmi160.hpp:269
perf_counter_t _sample_perf
Definition: bmi160.hpp:281
void test_error()
trigger an error
perf_counter_t _accel_reads
Definition: bmi160.hpp:279
Report conversation within the BMI160, including command byte and interrupt status.
Definition: bmi160.hpp:403
perf_counter_t _good_transfers
Definition: bmi160.hpp:284
Header common to all counters.
void init()
Activates/configures the hardware registers.
Definition of commonly used conversions.
int16_t accel_y
Definition: bmi160.hpp:409
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
int16_t gyro_z
Definition: bmi160.hpp:407
perf_counter_t _duplicates
Definition: bmi160.hpp:286
perf_counter_t _bad_registers
Definition: bmi160.hpp:283
perf_counter_t _gyro_reads
Definition: bmi160.hpp:280
unsigned _dlpf_freq
whoami result
Definition: bmi160.hpp:274
perf_counter_t _reset_retries
Definition: bmi160.hpp:285
uint16_t swap16(uint16_t val)
Swap a 16-bit value read from the BMI160 to native byte order.
Definition: bmi160.hpp:377
int16_t gyro_x
Definition: bmi160.hpp:405
static int start()
Definition: dataman.cpp:1452
int16_t accel_z
Definition: bmi160.hpp:410
int16_t accel_x
Definition: bmi160.hpp:408
uint8_t _whoami
Definition: bmi160.hpp:272
perf_counter_t _bad_transfers
Definition: bmi160.hpp:282
#define BMI160_ACCEL_DEFAULT_RATE
Definition: bmi160.hpp:227
static constexpr uint8_t _checked_registers[]
Definition: FXAS21002C.cpp:178
Performance measuring tools.