PX4 Firmware
PX4 Autopilot Software http://px4.io
BMI088_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 
36 #include "BMI088.hpp"
37 
40 
41 #define BMI088_DEVICE_PATH_ACCEL "/dev/bmi088_accel"
42 #define BMI088_DEVICE_PATH_ACCEL_EXT "/dev/bmi088_accel_ext"
43 
44 // BMI088 Accel registers
45 #define BMI088_ACC_CHIP_ID 0x00
46 
47 #define BMI088_ACC_ERR_REG 0x02
48 #define BMI088_ACC_STATUS 0x03
49 #define BMI088_ACC_X_L 0x12
50 #define BMI088_ACC_X_H 0x13
51 #define BMI088_ACC_Y_L 0x14
52 #define BMI088_ACC_Y_H 0x15
53 #define BMI088_ACC_Z_L 0x16
54 #define BMI088_ACC_Z_H 0x17
55 #define BMI088_ACC_SENSORTIME_0 0x18
56 #define BMI088_ACC_SENSORTIME_1 0x19
57 #define BMI088_ACC_SENSORTIME_2 0x1A
58 #define BMI088_ACC_INT_STAT_1 0x1D
59 #define BMI088_ACC_TEMP_H 0x22
60 #define BMI088_ACC_TEMP_L 0x23
61 #define BMI088_ACC_CONF 0x40
62 #define BMI088_ACC_RANGE 0x41
63 #define BMI088_ACC_INT1_IO_CONF 0x53
64 #define BMI088_ACC_INT2_IO_CONF 0x54
65 #define BMI088_ACC_INT1_INT2_MAP_DATA 0x58
66 #define BMI088_ACC_SELF_TEST 0x6D
67 #define BMI088_ACC_PWR_CONF 0x7C
68 #define BMI088_ACC_PWR_CTRL 0x7D
69 #define BMI088_ACC_SOFTRESET 0x7E
70 
71 // BMI088 Accelerometer Chip-Id
72 #define BMI088_ACC_WHO_AM_I 0x1E
73 
74 // BMI088_ACC_ERR_REG 0x02
75 #define BMI088_ACC_ERR_REG_NO_ERROR (0x00<<2)
76 #define BMI088_ACC_ERR_REG_ERROR (0x01<<2)
77 
78 #define BMI088_ACC_ERR_REG_FATAL_ERROR (0x01<<0)
79 
80 // BMI088_ACC_STATUS 0x03
81 #define BMI088_ACC_STATUS_DRDY (0x01<<7)
82 
83 // BMI088_ACC_INT_STAT_1 0x01D
84 #define BMI088_ACC_INT_STAT_1_DRDY (0x01<<7)
85 
86 // BMI088_ACC_CONF 0x40
87 #define BMI088_ACC_CONF_BWP_4 (0x08<<4)
88 #define BMI088_ACC_CONF_BWP_2 (0x09<<4)
89 #define BMI088_ACC_CONF_BWP_NORMAL (0x0A<<4)
90 
91 #define BMI088_ACC_CONF_ODR_12_5 (0x05<<0)
92 #define BMI088_ACC_CONF_ODR_25 (0x06<<0)
93 #define BMI088_ACC_CONF_ODR_50 (0x07<<0)
94 #define BMI088_ACC_CONF_ODR_100 (0x08<<0)
95 #define BMI088_ACC_CONF_ODR_200 (0x09<<0)
96 #define BMI088_ACC_CONF_ODR_400 (0x0A<<0)
97 #define BMI088_ACC_CONF_ODR_800 (0x0B<<0)
98 #define BMI088_ACC_CONF_ODR_1600 (0x0C<<0)
99 
100 // BMI088_ACC_RANGE 0x41
101 #define BMI088_ACCEL_RANGE_3_G (0x00<<0)
102 #define BMI088_ACCEL_RANGE_6_G (0x01<<0)
103 #define BMI088_ACCEL_RANGE_12_G (0x02<<0)
104 #define BMI088_ACCEL_RANGE_24_G (0x03<<0)
105 
106 // BMI088_ACC_INT1_IO_CONF 0x53
107 #define BMI088_ACC_INT1_IO_CONF_INT1_IN (0x01<<4)
108 
109 #define BMI088_ACC_INT1_IO_CONF_INT1_OUT (0x01<<3)
110 
111 #define BMI088_ACC_INT1_IO_CONF_PP (0x00<<2)
112 #define BMI088_ACC_INT1_IO_CONF_OD (0x01<<2)
113 
114 #define BMI088_ACC_INT1_IO_CONF_ACTIVE_LOW (0x00<<1)
115 #define BMI088_ACC_INT1_IO_CONF_ACTIVE_HIGH (0x01<<1)
116 
117 // BMI088_ACC_INT2_IO_CONF 0x54
118 #define BMI088_ACC_INT2_IO_CONF_INT1_IN (0x01<<4)
119 
120 #define BMI088_ACC_INT2_IO_CONF_INT1_OUT (0x01<<3)
121 
122 #define BMI088_ACC_INT2_IO_CONF_PP (0x00<<2)
123 #define BMI088_ACC_INT2_IO_CONF_OD (0x01<<2)
124 
125 #define BMI088_ACC_INT2_IO_CONF_ACTIVE_LOW (0x00<<1)
126 #define BMI088_ACC_INT2_IO_CONF_ACTIVE_HIGH (0x01<<1)
127 
128 // BMI088_ACC_INT1_INT2_MAP_DATA 0x54
129 #define BMI088_ACC_INT1_INT2_MAP_DATA_INT2_DRDY (0x01<<6)
130 #define BMI088_ACC_INT1_INT2_MAP_DATA_INT1_DRDY (0x01<<2)
131 
132 // BMI088_ACC_SELF_TEST 0x6D
133 #define BMI088_ACC_SELF_TEST_OFF (0x00<<0)
134 #define BMI088_ACC_SELF_TEST_POSITIVE (0x0D<<0)
135 #define BMI088_ACC_SELF_TEST_NEGATIVE (0x09<<0)
136 
137 // BMI088_ACC_PWR_CONF 0x7C
138 #define BMI088_ACC_PWR_CONF_SUSPEND (0x03<<0)
139 #define BMI088_ACC_PWR_CONF_ACTIVE (0x00<<0)
140 
141 // BMI088_ACC_PWR_CTRL 0x7D
142 #define BMI088_ACC_PWR_CTRL_EN (0x04<<0)
143 
144 
145 ///////
146 // To Do check these defaults and maks below
147 ///
148 
149 // Default and Max values
150 #define BMI088_ACCEL_DEFAULT_RANGE_G 24
151 #define BMI088_ACCEL_DEFAULT_RATE 800
152 #define BMI088_ACCEL_MAX_RATE 800
153 #define BMI088_ACCEL_MAX_PUBLISH_RATE 800
154 
155 #define BMI088_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 50
156 
157 class BMI088_accel : public BMI088, public px4::ScheduledWorkItem
158 {
159 public:
160  BMI088_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation);
161  virtual ~BMI088_accel();
162 
163  virtual int init();
164 
165  // Start automatic measurement.
166  void start();
167 
168  // We need to override the read_reg function from the BMI088 base class, because the accelerometer requires a dummy byte read before each read operation
169  virtual uint8_t read_reg(unsigned reg);
170 
171  // We need to override the read_reg16 function from the BMI088 base class, because the accelerometer requires a dummy byte read before each read operation
172  virtual uint16_t read_reg16(unsigned reg);
173 
174  /**
175  * Diagnostics - print some basic information about the driver.
176  */
177  void print_info();
178 
179  void print_registers();
180 
181  // deliberately cause a sensor error
182  void test_error();
183 
184 protected:
185 
186  virtual int probe();
187 
188 private:
189 
191 
196 
197  // this is used to support runtime checking of key
198  // configuration registers to detect SPI bus errors and sensor
199  // reset
200 #define BMI088_ACCEL_NUM_CHECKED_REGISTERS 7
204 
206 
207  /**
208  * Stop automatic measurement.
209  */
210  void stop();
211 
212  /**
213  * Reset chip.
214  *
215  * Resets the chip and measurements ranges, but not scale and offset.
216  */
217  int reset();
218 
219  void Run() override;
220 
221  /**
222  * Fetch measurements from the sensor and update the report buffers.
223  */
224  void measure();
225 
226  /**
227  * Modify a register in the BMI088_accel
228  *
229  * Bits are cleared before bits are set.
230  *
231  * @param reg The register to modify.
232  * @param clearbits Bits in the register to clear.
233  * @param setbits Bits in the register to set.
234  */
235  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
236 
237  /**
238  * Write a register in the BMI088_accel, updating _checked_values
239  *
240  * @param reg The register to write.
241  * @param value The new value to write.
242  */
243  void write_checked_reg(unsigned reg, uint8_t value);
244 
245  /**
246  * Set the BMI088_accel measurement range.
247  *
248  * @param max_g The maximum G value the range must support.
249  * @return OK if the value can be supported, -EINVAL otherwise.
250  */
251  int set_accel_range(unsigned max_g);
252 
253  /**
254  * Set accel sample rate
255  */
256  int accel_set_sample_rate(float desired_sample_rate_hz);
257 
258  /*
259  * check that key registers still have the right value
260  */
261  void check_registers(void);
262 
263  /* do not allow to copy this class due to pointer data members */
264  BMI088_accel(const BMI088_accel &);
266 
267 };
void measure()
Fetch measurements from the sensor and update the report buffers.
virtual uint8_t read_reg(unsigned reg)
Read a register from the BMI088.
void print_info()
Diagnostics - print some basic information about the driver.
perf_counter_t _bad_registers
int reset()
Reset chip.
void Run() override
int accel_set_sample_rate(float desired_sample_rate_hz)
Set accel sample rate.
int set_accel_range(unsigned max_g)
Set the BMI088_accel measurement range.
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
BMI088_accel operator=(const BMI088_accel &)
perf_counter_t _duplicates
Vector rotation library.
BMI088_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation)
virtual ~BMI088_accel()
#define BMI088_ACCEL_NUM_CHECKED_REGISTERS
uint8_t _checked_bad[BMI088_ACCEL_NUM_CHECKED_REGISTERS]
Header common to all counters.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the BMI088_accel, updating _checked_values.
perf_counter_t _sample_perf
virtual int probe()
perf_counter_t _bad_transfers
virtual int init()
PX4Accelerometer _px4_accel
static const uint8_t _checked_registers[BMI088_ACCEL_NUM_CHECKED_REGISTERS]
void stop()
Stop automatic measurement.
void check_registers(void)
virtual uint16_t read_reg16(unsigned reg)
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the BMI088_accel.
void print_registers()
uint8_t _checked_values[BMI088_ACCEL_NUM_CHECKED_REGISTERS]