PX4 Firmware
PX4 Autopilot Software http://px4.io
bmm150.hpp
Go to the documentation of this file.
1 #ifndef BMM150_HPP_
2 #define BMM150_HPP_
3 
4 #include <px4_platform_common/px4_config.h>
5 
6 #include <sys/types.h>
7 #include <stdint.h>
8 #include <stdbool.h>
9 #include <stddef.h>
10 #include <stdlib.h>
11 #include <semaphore.h>
12 #include <string.h>
13 #include <fcntl.h>
14 #include <poll.h>
15 #include <errno.h>
16 #include <stdio.h>
17 #include <math.h>
18 #include <unistd.h>
19 #include <px4_platform_common/log.h>
20 
21 #include <perf/perf_counter.h>
22 #include <systemlib/err.h>
23 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
24 #include <systemlib/conversions.h>
25 
26 #include <nuttx/arch.h>
27 #include <nuttx/clock.h>
28 
29 #include <board_config.h>
30 #include <drivers/drv_hrt.h>
31 
34 #include <drivers/device/i2c.h>
35 #include <drivers/drv_mag.h>
38 
39 
40 #define BMM150_DEVICE_PATH_MAG "/dev/bmm150_i2c_int"
41 
42 #define BMM150_DEVICE_PATH_MAG_EXT "/dev/bmm150_i2c_ext"
43 
44 #define BMM150_SLAVE_ADDRESS 0x10
45 
46 #define BMM150_BUS_SPEED 1000*100
47 
48 /* Chip Identification number */
49 #define BMM150_CHIP_ID 0x32
50 
51 /* Chip Id Register */
52 #define BMM150_CHIP_ID_REG 0x40
53 
54 /* Data Registers */
55 #define BMM150_DATA_X_LSB_REG 0x42
56 #define BMM150_DATA_X_MSB_REG 0x43
57 #define BMM150_DATA_Y_LSB_REG 0x44
58 #define BMM150_DATA_Y_MSB_REG 0x45
59 #define BMM150_DATA_Z_LSB_REG 0x46
60 #define BMM150_DATA_Z_MSB_REG 0x47
61 #define BMM150_R_LSB 0x48
62 #define BMM150_R_MSB 0x49
63 
64 /* Interrupt status registers */
65 #define BMM150_INT_STATUS_REG 0x4A
66 
67 /* Control Registers */
68 #define BMM150_POWER_CTRL_REG 0x4B
69 #define BMM150_CTRL_REG 0x4C
70 #define BMM150_INT_SETT_CTRL_REG 0x4D
71 #define BMM150_AXES_EN_CTRL_REG 0x4E
72 #define BMM150_LOW_THRES_SETT_REG 0x4F
73 #define BMM150_HIGH_THERS_SETT_REG 0x50
74 
75 /* Repetitions control registers */
76 #define BMM150_XY_REP_CTRL_REG 0x51
77 #define BMM150_Z_REP_CTRL_REG 0x52
78 
79 /* Preset mode definitions */
80 #define BMM150_PRESETMODE_LOWPOWER 1
81 #define BMM150_PRESETMODE_REGULAR 2
82 #define BMM150_PRESETMODE_HIGHACCURACY 3
83 #define BMM150_PRESETMODE_ENHANCED 4
84 
85 
86 /* Data rate value definitions */
87 #define BMM150_DATA_RATE_10HZ 0x00
88 #define BMM150_DATA_RATE_02HZ 0x08
89 #define BMM150_DATA_RATE_06HZ 0x10
90 #define BMM150_DATA_RATE_08HZ 0x18
91 #define BMM150_DATA_RATE_15HZ 0x20
92 #define BMM150_DATA_RATE_20HZ 0x28
93 #define BMM150_DATA_RATE_25HZ 0x30
94 #define BMM150_DATA_RATE_30HZ 0x38
95 
96 /* Advance self-test settings Definitions */
97 #define BMM150_ADV_ST_OFF 0x00
98 #define BMM150_ADV_ST_NEG 0x80
99 #define BMM150_ADV_ST_POS 0xC0
100 
101 
102 /* Interrupt settings and axes enable bits definitions */
103 #define BMM150_CHANNEL_X_ENABLE 0x08
104 #define BMM150_CHANNEL_Y_ENABLE 0x10
105 
106 
107 /*Overflow Definitions */
108 /* compensated output value returned if sensor had overflow */
109 #define BMM150_OVERFLOW_OUTPUT -32768
110 #define BMM150_OVERFLOW_OUTPUT_S32 ((int32_t)(-2147483647-1))
111 #define BMM150_OVERFLOW_OUTPUT_FLOAT 0.0f
112 #define BMM150_FLIP_OVERFLOW_ADCVAL -4096
113 #define BMM150_HALL_OVERFLOW_ADCVAL -16384
114 
115 
116 /* Preset modes - Repetitions-XY Rates */
117 #define BMM150_LOWPOWER_REPXY 1
118 #define BMM150_REGULAR_REPXY 4
119 #define BMM150_HIGHACCURACY_REPXY 23
120 #define BMM150_ENHANCED_REPXY 7
121 
122 /* Preset modes - Repetitions-Z Rates */
123 #define BMM150_LOWPOWER_REPZ 2
124 #define BMM150_REGULAR_REPZ 14
125 #define BMM150_HIGHACCURACY_REPZ 82
126 #define BMM150_ENHANCED_REPZ 26
127 
128 /* Preset modes - Data rates */
129 #define BMM150_LOWPOWER_DR BMM150_DATA_RATE_30HZ
130 #define BMM150_REGULAR_DR BMM150_DATA_RATE_30HZ
131 #define BMM150_HIGHACCURACY_DR BMM150_DATA_RATE_20HZ
132 #define BMM150_ENHANCED_DR BMM150_DATA_RATE_10HZ
133 
134 
135 /* Power modes value definitions */
136 #define BMM150_NORMAL_MODE 0x00
137 #define BMM150_FORCED_MODE 0x02
138 #define BMM150_SLEEP_MODE 0x06
139 
140 /* Default power mode */
141 #define BMM150_DEFAULT_POWER_MODE BMM150_NORMAL_MODE
142 
143 /* Default output data rate */
144 #define BMM150_DEFAULT_ODR BMM150_DATA_RATE_30HZ
145 
146 /* Maximum output data rate */
147 #define BMM150_MAX_DATA_RATE 100
148 
149 /* Default BMM150_INT_SETT_CTRL_REG Value */
150 #define BMM150_DEFAULT_INT_SETT 0x3F
151 
152 /* Trim Extended Registers */
153 #define BMM150_DIG_X1 0x5D
154 #define BMM150_DIG_Y1 0x5E
155 #define BMM150_DIG_Z4_LSB 0x62
156 #define BMM150_DIG_Z4_MSB 0x63
157 #define BMM150_DIG_X2 0x64
158 #define BMM150_DIG_Y2 0x65
159 #define BMM150_DIG_Z2_LSB 0x68
160 #define BMM150_DIG_Z2_MSB 0x69
161 #define BMM150_DIG_Z1_LSB 0x6A
162 #define BMM150_DIG_Z1_MSB 0x6B
163 #define BMM150_DIG_XYZ1_LSB 0x6C
164 #define BMM150_DIG_XYZ1_MSB 0x6D
165 #define BMM150_DIG_Z3_LSB 0x6E
166 #define BMM150_DIG_Z3_MSB 0x6F
167 #define BMM150_DIG_XY2 0x70
168 #define BMM150_DIG_XY1 0x71
169 
170 
171 /* Mask definitions for power mode */
172 #define BMM150_POWER_MASK 0x06
173 
174 /* Mask definitions for data rate */
175 #define BMM150_OUTPUT_DATA_RATE_MASK 0x38
176 
177 #define BMM150_SOFT_RESET_VALUE 0x82
178 
179 /* Mask definitions for Soft-Reset */
180 #define BMM150_SOFT_RESET_MASK 0x82
181 
182 /* This value is set based on Max output data rate value */
183 #define BMM150_CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
184 
185 
186 
187 struct bmm150_data {
188  int16_t x;
189  int16_t y;
190  int16_t z;
191 };
192 
193 
194 class BMM150 : public device::I2C, public px4::ScheduledWorkItem
195 {
196 public:
197  BMM150(int bus, const char *path, enum Rotation rotation);
198  virtual ~BMM150();
199 
200  virtual int init();
201  virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
202  virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
203 
204  /**
205  * Stop automatic measurement.
206  */
207  void stop();
208 
209  /**
210  * Diagnostics - print some basic information about the driver.
211  */
212  void print_info();
213 
214  void print_registers();
215 
216 protected:
217  virtual int probe();
218 
219 private:
220 
221  bool _running;
222 
223  /* altitude conversion calibration */
224  unsigned _call_interval;
225 
226 
227  mag_report _report {};
228  ringbuffer::RingBuffer *_reports;
229 
231 
232  struct mag_calibration_s _scale;
234 
238  uint8_t _power;
240  bool _calibrated; /**< the calibration is valid */
241 
242  int8_t dig_x1;/**< trim x1 data */
243  int8_t dig_y1;/**< trim y1 data */
244 
245  int8_t dig_x2;/**< trim x2 data */
246  int8_t dig_y2;/**< trim y2 data */
247 
248  uint16_t dig_z1;/**< trim z1 data */
249  int16_t dig_z2;/**< trim z2 data */
250  int16_t dig_z3;/**< trim z3 data */
251  int16_t dig_z4;/**< trim z4 data */
252 
253  uint8_t dig_xy1;/**< trim xy1 data */
254  int8_t dig_xy2;/**< trim xy2 data */
255 
256  uint16_t dig_xyz1;/**< trim xyz1 data */
257 
264 
265  enum Rotation _rotation;
267 
268  mag_report _last_report {}; /**< used for info() */
269 
270  int init_trim_registers(void);
271 
272  /**
273  * Start automatic measurement.
274  */
275  void start();
276 
277  int measure(); //start measure
278  int collect(); //get results and publish
279 
280  void Run() override;
281 
282  /**
283  * Read the specified number of bytes from BMM150.
284  *
285  * @param reg The register to read.
286  * @param data Pointer to buffer for bytes read.
287  * @param len Number of bytes to read
288  * @return OK if the transfer was successful, -errno otherwise.
289  */
290  int get_data(uint8_t reg, uint8_t *data, unsigned len);
291 
292  /**
293  * Resets the chip.
294  */
295  int reset();
296 
297  /**
298  * Measurement self test
299  *
300  * @return 0 on success, 1 on failure
301  */
302  int self_test();
303 
304  /**
305  * Read a register from the BMM150
306  *
307  * @param reg The register to read.
308  * @return The value that was read.
309  */
310  uint8_t read_reg(uint8_t reg);
311 
312  /**
313  * Write a register in the BMM150
314  *
315  * @param reg The register to write.
316  * @param value The new value to write.
317  * @return OK if the transfer was successful, -errno otherwise.
318  */
319  int write_reg(uint8_t reg, uint8_t value);
320 
321  /**
322  * Modify a register in the BMM150
323  *
324  * Bits are cleared before bits are set.
325  *
326  * @param reg The register to modify.
327  * @param clearbits Bits in the register to clear.
328  * @param setbits Bits in the register to set.
329  */
330  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
331 
332  /*
333  set the power mode of BMM150.
334  */
335  int set_power_mode(uint8_t power);
336 
337  /*
338  Set the data rate of BMM150.
339  */
340  int set_data_rate(uint8_t data_rate);
341 
342  /*
343  Set the XY-repetitions
344  */
345  int set_rep_xy(uint8_t rep_xy);
346 
347  /*
348  Set the Z- repetitions number
349  */
350  int set_rep_z(uint8_t rep_z);
351 
352  /*
353  Set the preset modes for BMM150 sensor.The preset mode setting is
354  depend on Data Rate, XY and Z repetitions
355  */
356  int set_presetmode(uint8_t presetmode);
357 
358 
359  /* do not allow to copy this class due to pointer data members */
360  BMM150(const BMM150 &);
361  BMM150 operator=(const BMM150 &);
362 
363 };
364 
365 
366 
367 #endif /* BMM150_HPP_ */
int8_t dig_x2
trim x2 data
Definition: bmm150.hpp:245
int _orb_class_instance
Definition: bmm150.hpp:236
uint16_t dig_xyz1
trim xyz1 data
Definition: bmm150.hpp:256
perf_counter_t _comms_errors
Definition: bmm150.hpp:262
int16_t x
Definition: bmm150.hpp:188
mag scaling factors; Vout = (Vin * Vscale) + Voffset
Definition: drv_mag.h:56
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static void stop()
Definition: dataman.cpp:1491
int8_t dig_y2
trim y2 data
Definition: bmm150.hpp:246
Vector rotation library.
bool _got_duplicate
Definition: bmm150.hpp:266
High-resolution timer with callouts and timekeeping.
unsigned _call_interval
Definition: bmm150.hpp:224
float _range_scale
Definition: bmm150.hpp:233
perf_counter_t _duplicates
Definition: bmm150.hpp:263
ringbuffer::RingBuffer * _reports
Definition: bmm150.hpp:228
int8_t dig_y1
trim y1 data
Definition: bmm150.hpp:243
uint8_t _power
Definition: bmm150.hpp:238
static void read(bootloader_app_shared_t *pshared)
int16_t z
Definition: bmm150.hpp:190
uint16_t dig_z1
trim z1 data
Definition: bmm150.hpp:248
uint8_t dig_xy1
trim xy1 data
Definition: bmm150.hpp:253
int8_t dig_x1
trim x1 data
Definition: bmm150.hpp:242
Header common to all counters.
bool _running
Definition: bmm150.hpp:221
int16_t y
Definition: bmm150.hpp:189
void init()
Activates/configures the hardware registers.
Definition of commonly used conversions.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t * data
Definition: dataman.cpp:149
perf_counter_t _good_transfers
Definition: bmm150.hpp:260
int16_t dig_z4
trim z4 data
Definition: bmm150.hpp:251
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
perf_counter_t _measure_perf
Definition: bmm150.hpp:261
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
perf_counter_t _bad_transfers
Definition: bmm150.hpp:259
static int start()
Definition: dataman.cpp:1452
A resettable integrator.
int16_t dig_z2
trim z2 data
Definition: bmm150.hpp:249
uint8_t _output_data_rate
Definition: bmm150.hpp:239
struct @83::@85::@87 file
int16_t dig_z3
trim z3 data
Definition: bmm150.hpp:250
int _class_instance
Definition: bmm150.hpp:237
orb_advert_t _topic
Definition: bmm150.hpp:235
perf_counter_t _sample_perf
Definition: bmm150.hpp:258
bool _calibrated
the calibration is valid
Definition: bmm150.hpp:240
int8_t dig_xy2
trim xy2 data
Definition: bmm150.hpp:254
bool _collect_phase
Definition: bmm150.hpp:230
Performance measuring tools.
Base class for devices connected via I2C.
#define mag_report
Definition: drv_mag.h:53