PX4 Firmware
PX4 Autopilot Software http://px4.io
BMI055_gyro.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_GYRO "/dev/bmi055_gyro"
41 #define BMI055_DEVICE_PATH_GYRO_EXT "/dev/bmi055_gyro_ext"
42 
43 // BMI055 Gyro registers
44 #define BMI055_GYR_CHIP_ID 0x00
45 #define BMI055_GYR_X_L 0x02
46 #define BMI055_GYR_X_H 0x03
47 #define BMI055_GYR_Y_L 0x04
48 #define BMI055_GYR_Y_H 0x05
49 #define BMI055_GYR_Z_L 0x06
50 #define BMI055_GYR_Z_H 0x07
51 #define BMI055_GYR_INT_STATUS_0 0x09
52 #define BMI055_GYR_INT_STATUS_1 0x0A
53 #define BMI055_GYR_INT_STATUS_2 0x0B
54 #define BMI055_GYR_INT_STATUS_3 0x0C
55 #define BMI055_GYR_FIFO_STATUS 0x0E
56 #define BMI055_GYR_RANGE 0x0F
57 #define BMI055_GYR_BW 0x10
58 #define BMI055_GYR_LPM1 0x11
59 #define BMI055_GYR_LPM2 0x12
60 #define BMI055_GYR_RATE_HBW 0x13
61 #define BMI055_GYR_SOFTRESET 0x14
62 #define BMI055_GYR_INT_EN_0 0x15
63 #define BMI055_GYR_INT_EN_1 0x16
64 #define BMI055_GYR_INT_MAP_0 0x17
65 #define BMI055_GYR_INT_MAP_1 0x18
66 #define BMI055_GYR_INT_MAP_2 0x19
67 #define BMI055_GYRO_0_REG 0x1A
68 #define BMI055_GYRO_1_REG 0x1B
69 #define BMI055_GYRO_2_REG 0x1C
70 #define BMI055_GYRO_3_REG 0x1E
71 #define BMI055_GYR_INT_LATCH 0x21
72 #define BMI055_GYR_INT_LH_0 0x22
73 #define BMI055_GYR_INT_LH_1 0x23
74 #define BMI055_GYR_INT_LH_2 0x24
75 #define BMI055_GYR_INT_LH_3 0x25
76 #define BMI055_GYR_INT_LH_4 0x26
77 #define BMI055_GYR_INT_LH_5 0x27
78 #define BMI055_GYR_SOC 0x31
79 #define BMI055_GYR_A_FOC 0x32
80 #define BMI055_GYR_TRIM_NVM_CTRL 0x33
81 #define BMI055_BGW_SPI3_WDT 0x34
82 #define BMI055_GYR_OFFSET_COMP 0x36
83 #define BMI055_GYR_OFFSET_COMP_X 0x37
84 #define BMI055_GYR_OFFSET_COMP_Y 0x38
85 #define BMI055_GYR_OFFSET_COMP_Z 0x39
86 #define BMI055_GYR_TRIM_GPO 0x3A
87 #define BMI055_GYR_TRIM_GP1 0x3B
88 #define BMI055_GYR_SELF_TEST 0x3C
89 #define BMI055_GYR_FIFO_CONFIG_0 0x3D
90 #define BMI055_GYR_FIFO_CONFIG_1 0x3E
91 #define BMI055_GYR_FIFO_DATA 0x3F
92 
93 // BMI055 Gyroscope Chip-Id
94 #define BMI055_GYR_WHO_AM_I 0x0F
95 
96 // ODR & DLPF filter bandwidth settings (they are coupled)
97 #define BMI055_GYRO_RATE_100 (0<<3) | (1<<2) | (1<<1) | (1<<0)
98 #define BMI055_GYRO_RATE_200 (0<<3) | (1<<2) | (1<<1) | (0<<0)
99 #define BMI055_GYRO_RATE_400 (0<<3) | (0<<2) | (1<<1) | (1<<0)
100 #define BMI055_GYRO_RATE_1000 (0<<3) | (0<<2) | (1<<1) | (0<<0)
101 #define BMI055_GYRO_RATE_2000 (0<<3) | (0<<2) | (0<<1) | (1<<0)
102 
103 //BMI055_GYR_LPM1 0x11
104 #define BMI055_GYRO_NORMAL (0<<7) | (0<<5)
105 #define BMI055_GYRO_DEEP_SUSPEND (0<<7) | (1<<5)
106 #define BMI055_GYRO_SUSPEND (1<<7) | (0<<5)
107 
108 //BMI055_GYR_RANGE 0x0F
109 #define BMI055_GYRO_RANGE_2000_DPS (0<<2) | (0<<1) | (0<<0)
110 #define BMI055_GYRO_RANGE_1000_DPS (0<<2) | (0<<1) | (1<<0)
111 #define BMI055_GYRO_RANGE_500_DPS (0<<2) | (1<<1) | (0<<0)
112 #define BMI055_GYRO_RANGE_250_DPS (0<<2) | (1<<1) | (1<<0)
113 #define BMI055_GYRO_RANGE_125_DPS (1<<2) | (0<<1) | (0<<0)
114 
115 //BMI055_GYR_INT_EN_0 0x15
116 #define BMI055_GYR_DRDY_INT_EN (1<<7)
117 
118 //BMI055_GYR_INT_MAP_1 0x18
119 #define BMI055_GYR_DRDY_INT1 (1<<0)
120 
121 // Default and Max values
122 #define BMI055_GYRO_DEFAULT_RANGE_DPS 2000
123 #define BMI055_GYRO_DEFAULT_RATE 1000
124 #define BMI055_GYRO_MAX_RATE 1000
125 #define BMI055_GYRO_MAX_PUBLISH_RATE 280
126 
127 #define BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ 50
128 
129 /* Mask definitions for Gyro bandwidth */
130 #define BMI055_GYRO_BW_MASK 0x0F
131 
132 #define BMI055_ACC_TEMP 0x08
133 
134 class BMI055_gyro : public BMI055, public px4::ScheduledWorkItem
135 {
136 public:
137  BMI055_gyro(int bus, const char *path_gyro, uint32_t device, enum Rotation rotation);
138  virtual ~BMI055_gyro();
139 
140  virtual int init();
141 
142  // Start automatic measurement.
143  void start();
144 
145  /**
146  * Diagnostics - print some basic information about the driver.
147  */
148  void print_info();
149 
150  void print_registers();
151 
152  // deliberately cause a sensor error
153  void test_error();
154 
155 protected:
156 
157  virtual int probe();
158 
159 private:
160 
162 
166 
167  // this is used to support runtime checking of key
168  // configuration registers to detect SPI bus errors and sensor
169  // reset
170 #define BMI055_GYRO_NUM_CHECKED_REGISTERS 7
174 
175  /**
176  * Stop automatic measurement.
177  */
178  void stop();
179 
180  /**
181  * Reset chip.
182  *
183  * Resets the chip and measurements ranges, but not scale and offset.
184  */
185  int reset();
186 
187  void Run() override;
188 
189  /**
190  * Fetch measurements from the sensor and update the report buffers.
191  */
192  void measure();
193 
194  /**
195  * Modify a register in the BMI055_gyro
196  *
197  * Bits are cleared before bits are set.
198  *
199  * @param reg The register to modify.
200  * @param clearbits Bits in the register to clear.
201  * @param setbits Bits in the register to set.
202  */
203  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
204 
205  /**
206  * Write a register in the BMI055_gyro, updating _checked_values
207  *
208  * @param reg The register to write.
209  * @param value The new value to write.
210  */
211  void write_checked_reg(unsigned reg, uint8_t value);
212 
213  /**
214  * Set the BMI055_gyro measurement range.
215  *
216  * @param max_dps The maximum DPS value the range must support.
217  * @return OK if the value can be supported, -EINVAL otherwise.
218  */
219  int set_gyro_range(unsigned max_dps);
220 
221  /*
222  * set gyro sample rate
223  */
224  int gyro_set_sample_rate(float desired_sample_rate_hz);
225 
226  /*
227  * check that key registers still have the right value
228  */
229  void check_registers(void);
230 
231  /* do not allow to copy this class due to pointer data members */
232  BMI055_gyro(const BMI055_gyro &);
234 
235 #pragma pack(push, 1)
236  /**
237  * Report conversation within the BMI055_gyro, including command byte and
238  * interrupt status.
239  */
240  struct BMI_GyroReport {
241  uint8_t cmd;
242  int16_t gyro_x;
243  int16_t gyro_y;
244  int16_t gyro_z;
245  };
246 #pragma pack(pop)
247 
248 };
PX4Gyroscope _px4_gyro
int gyro_set_sample_rate(float desired_sample_rate_hz)
uint8_t _checked_bad[BMI055_GYRO_NUM_CHECKED_REGISTERS]
void check_registers(void)
Report conversation within the BMI055_gyro, including command byte and interrupt status.
int set_gyro_range(unsigned max_dps)
Set the BMI055_gyro measurement range.
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
int reset()
Reset chip.
Definition: BMI055_gyro.cpp:87
virtual int init()
Definition: BMI055_gyro.cpp:73
void print_registers()
void measure()
Fetch measurements from the sensor and update the report buffers.
Header common to all counters.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
perf_counter_t _bad_registers
static const uint8_t _checked_registers[BMI055_GYRO_NUM_CHECKED_REGISTERS]
perf_counter_t _bad_transfers
void stop()
Stop automatic measurement.
uint8_t _checked_values[BMI055_GYRO_NUM_CHECKED_REGISTERS]
#define BMI055_GYRO_NUM_CHECKED_REGISTERS
virtual int probe()
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the BMI055_gyro.
BMI055_gyro(int bus, const char *path_gyro, uint32_t device, enum Rotation rotation)
Definition: BMI055_gyro.cpp:50
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the BMI055_gyro, updating _checked_values.
virtual ~BMI055_gyro()
Definition: BMI055_gyro.cpp:61
void Run() override
perf_counter_t _sample_perf
BMI055_gyro operator=(const BMI055_gyro &)
void test_error()
void print_info()
Diagnostics - print some basic information about the driver.