PX4 Firmware
PX4 Autopilot Software http://px4.io
BMI055_accel.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 
37 
38 #include "BMI055.hpp"
39 
40 #define BMI055_DEVICE_PATH_ACCEL "/dev/bmi055_accel"
41 #define BMI055_DEVICE_PATH_ACCEL_EXT "/dev/bmi055_accel_ext"
42 
43 // BMI055 Accel registers
44 #define BMI055_ACC_CHIP_ID 0x00
45 #define BMI055_ACC_X_L 0x02
46 #define BMI055_ACC_X_H 0x03
47 #define BMI055_ACC_Y_L 0x04
48 #define BMI055_ACC_Y_H 0x05
49 #define BMI055_ACC_Z_L 0x06
50 #define BMI055_ACC_Z_H 0x07
51 #define BMI055_ACC_TEMP 0x08
52 #define BMI055_ACC_INT_STATUS_0 0x09
53 #define BMI055_ACC_INT_STATUS_1 0x0A
54 #define BMI055_ACC_INT_STATUS_2 0x0B
55 #define BMI055_ACC_INT_STATUS_3 0x0C
56 #define BMI055_ACC_FIFO_STATUS 0x0E
57 #define BMI055_ACC_RANGE 0x0F
58 #define BMI055_ACC_BW 0x10
59 #define BMI055_ACC_PMU_LPW 0x11
60 #define BMI055_ACC_PMU_LOW_POWER 0x12
61 #define BMI055_ACC_DATA_CTRL 0x13
62 #define BMI055_ACC_SOFTRESET 0x14
63 #define BMI055_ACC_INT_EN_0 0x16
64 #define BMI055_ACC_INT_EN_1 0x17
65 #define BMI055_ACC_INT_EN_2 0x18
66 #define BMI055_ACC_INT_MAP_0 0x19
67 #define BMI055_ACC_INT_MAP_1 0x1A
68 #define BMI055_ACC_INT_MAP_2 0x1B
69 #define BMI055_ACC_INT_SRC 0x1E
70 #define BMI055_ACC_INT_OUT_CTRL 0x20
71 #define BMI055_ACC_INT_LATCH 0x21
72 #define BMI055_ACC_INT_LH_0 0x22
73 #define BMI055_ACC_INT_LH_1 0x23
74 #define BMI055_ACC_INT_LH_2 0x24
75 #define BMI055_ACC_INT_LH_3 0x25
76 #define BMI055_ACC_INT_LH_4 0x26
77 #define BMI055_ACC_INT_MOT_0 0x27
78 #define BMI055_ACC_INT_MOT_1 0x28
79 #define BMI055_ACC_INT_MOT_2 0x29
80 #define BMI055_ACC_INT_TAP_0 0x2A
81 #define BMI055_ACC_INT_TAP_1 0x2B
82 #define BMI055_ACC_INT_ORIE_0 0x2C
83 #define BMI055_ACC_INT_ORIE_1 0x2D
84 #define BMI055_ACC_INT_FLAT_0 0x2E
85 #define BMI055_ACC_INT_FLAT_1 0x2F
86 #define BMI055_ACC_FIFO_CONFIG_0 0x30
87 #define BMI055_ACC_SELF_TEST 0x32
88 #define BMI055_ACC_EEPROM_CTRL 0x33
89 #define BMI055_ACC_SERIAL_CTRL 0x34
90 #define BMI055_ACC_OFFSET_CTRL 0x36
91 #define BMI055_ACC_OFC_SETTING 0x37
92 #define BMI055_ACC_OFFSET_X 0x38
93 #define BMI055_ACC_OFFSET_Y 0x39
94 #define BMI055_ACC_OFFSET_Z 0x3A
95 #define BMI055_ACC_TRIM_GPO 0x3B
96 #define BMI055_ACC_TRIM_GP1 0x3C
97 #define BMI055_ACC_FIFO_CONFIG_1 0x3E
98 #define BMI055_ACC_FIFO_DATA 0x3F
99 
100 // BMI055 Accelerometer Chip-Id
101 #define BMI055_ACC_WHO_AM_I 0xFA
102 
103 // DLPF filter bandwidth settings
104 #define BMI055_ACCEL_BW_7_81 (1<<3) | (0<<2) | (0<<1) | (0<<0)
105 #define BMI055_ACCEL_BW_15_63 (1<<3) | (0<<2) | (0<<1) | (1<<0)
106 #define BMI055_ACCEL_BW_31_25 (1<<3) | (0<<2) | (1<<1) | (0<<0)
107 #define BMI055_ACCEL_BW_62_5 (1<<3) | (0<<2) | (1<<1) | (1<<0)
108 #define BMI055_ACCEL_BW_125 (1<<3) | (1<<2) | (0<<1) | (0<<0)
109 #define BMI055_ACCEL_BW_250 (1<<3) | (1<<2) | (0<<1) | (1<<0)
110 #define BMI055_ACCEL_BW_500 (1<<3) | (1<<2) | (1<<1) | (0<<0)
111 #define BMI055_ACCEL_BW_1000 (1<<3) | (1<<2) | (1<<1) | (1<<0)
112 
113 //BMI055_ACC_PMU_LPW 0x11
114 #define BMI055_ACCEL_NORMAL (0<<7) | (0<<6) | (0<<5)
115 #define BMI055_ACCEL_DEEP_SUSPEND (0<<7) | (0<<6) | (1<<5)
116 #define BMI055_ACCEL_LOW_POWER (0<<7) | (1<<6) | (0<<5)
117 #define BMI055_ACCEL_SUSPEND (1<<7) | (0<<6) | (0<<5)
118 
119 //BMI055_ACC_RANGE 0x0F
120 #define BMI055_ACCEL_RANGE_2_G (0<<3) | (0<<2) | (1<<1) | (1<<0)
121 #define BMI055_ACCEL_RANGE_4_G (0<<3) | (1<<2) | (0<<1) | (1<<0)
122 #define BMI055_ACCEL_RANGE_8_G (1<<3) | (0<<2) | (0<<1) | (0<<0)
123 #define BMI055_ACCEL_RANGE_16_G (1<<3) | (1<<2) | (0<<1) | (0<<0)
124 
125 //BMI055_ACC_INT_EN_1 0x17
126 #define BMI055_ACC_DRDY_INT_EN (1<<4)
127 
128 //BMI055_ACC_INT_MAP_1 0x1A
129 #define BMI055_ACC_DRDY_INT1 (1<<0)
130 
131 // Default and Max values
132 #define BMI055_ACCEL_DEFAULT_RANGE_G 16
133 #define BMI055_ACCEL_DEFAULT_RATE 1000
134 #define BMI055_ACCEL_MAX_RATE 1000
135 #define BMI055_ACCEL_MAX_PUBLISH_RATE 280
136 
137 #define BMI055_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 50
138 
139 /* Mask definitions for ACCD_X_LSB, ACCD_Y_LSB and ACCD_Z_LSB Register */
140 #define BMI055_NEW_DATA_MASK 0x01
141 
142 class BMI055_accel : public BMI055, public px4::ScheduledWorkItem
143 {
144 public:
145  BMI055_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation);
146  virtual ~BMI055_accel();
147 
148  virtual int init();
149 
150  // Start automatic measurement.
151  void start();
152 
153  /**
154  * Diagnostics - print some basic information about the driver.
155  */
156  void print_info();
157 
158  void print_registers();
159 
160  // deliberately cause a sensor error
161  void test_error();
162 
163 protected:
164 
165  virtual int probe();
166 
167 private:
168 
170 
175 
176  // this is used to support runtime checking of key
177  // configuration registers to detect SPI bus errors and sensor
178  // reset
179 #define BMI055_ACCEL_NUM_CHECKED_REGISTERS 5
183 
185 
186  /**
187  * Stop automatic measurement.
188  */
189  void stop();
190 
191  /**
192  * Reset chip.
193  *
194  * Resets the chip and measurements ranges, but not scale and offset.
195  */
196  int reset();
197 
198  void Run() override;
199 
200  /**
201  * Fetch measurements from the sensor and update the report buffers.
202  */
203  void measure();
204 
205  /**
206  * Modify a register in the BMI055_accel
207  *
208  * Bits are cleared before bits are set.
209  *
210  * @param reg The register to modify.
211  * @param clearbits Bits in the register to clear.
212  * @param setbits Bits in the register to set.
213  */
214  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
215 
216  /**
217  * Write a register in the BMI055_accel, updating _checked_values
218  *
219  * @param reg The register to write.
220  * @param value The new value to write.
221  */
222  void write_checked_reg(unsigned reg, uint8_t value);
223 
224  /**
225  * Set the BMI055_accel measurement range.
226  *
227  * @param max_g The maximum G value the range must support.
228  * @return OK if the value can be supported, -EINVAL otherwise.
229  */
230  int set_accel_range(unsigned max_g);
231 
232  /*
233  * check that key registers still have the right value
234  */
235  void check_registers(void);
236 
237  /* do not allow to copy this class due to pointer data members */
238  BMI055_accel(const BMI055_accel &);
240 
241 };
virtual ~BMI055_accel()
BMI055_accel operator=(const BMI055_accel &)
void print_info()
Diagnostics - print some basic information about the driver.
uint8_t _checked_values[BMI055_ACCEL_NUM_CHECKED_REGISTERS]
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
static const uint8_t _checked_registers[BMI055_ACCEL_NUM_CHECKED_REGISTERS]
virtual int init()
perf_counter_t _duplicates
void print_registers()
perf_counter_t _sample_perf
int reset()
Reset chip.
Header common to all counters.
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the BMI055_accel.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t _checked_bad[BMI055_ACCEL_NUM_CHECKED_REGISTERS]
void Run() override
void measure()
Fetch measurements from the sensor and update the report buffers.
int set_accel_range(unsigned max_g)
Set the BMI055_accel measurement range.
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the BMI055_accel, updating _checked_values.
PX4Accelerometer _px4_accel
perf_counter_t _bad_registers
#define BMI055_ACCEL_NUM_CHECKED_REGISTERS
virtual int probe()
BMI055_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation)
void check_registers(void)
perf_counter_t _bad_transfers
void stop()
Stop automatic measurement.