PX4 Firmware
PX4 Autopilot Software http://px4.io
MPU9250_mag.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016-2019 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 <perf/perf_counter.h>
39 
40 /* in 16-bit sampling mode the mag resolution is 1.5 milli Gauss per bit */
41 static constexpr float MPU9250_MAG_RANGE_GA{1.5e-3f};
42 
43 /* ak8963 register address and bit definitions */
44 #define AK8963_I2C_ADDR 0x0C
45 #define AK8963_DEVICE_ID 0x48
46 
47 #define AK8963REG_WIA 0x00
48 #define AK8963REG_ST1 0x02
49 #define AK8963REG_HXL 0x03
50 #define AK8963REG_ASAX 0x10
51 #define AK8963REG_CNTL1 0x0A
52 #define AK8963REG_CNTL2 0x0B
53 
54 #define AK8963_SINGLE_MEAS_MODE 0x01
55 #define AK8963_CONTINUOUS_MODE1 0x02
56 #define AK8963_CONTINUOUS_MODE2 0x06
57 #define AK8963_POWERDOWN_MODE 0x00
58 #define AK8963_SELFTEST_MODE 0x08
59 #define AK8963_FUZE_MODE 0x0F
60 #define AK8963_16BIT_ADC 0x10
61 #define AK8963_14BIT_ADC 0x00
62 #define AK8963_RESET 0x01
63 #define AK8963_HOFL 0x08
64 
65 /* ak09916 deviating register addresses and bit definitions */
66 
67 #define AK09916_DEVICE_ID_A 0x48 // same as AK8963
68 #define AK09916_DEVICE_ID_B 0x09 // additional ID byte ("INFO" on AK9063 without content specification.)
69 
70 #define AK09916REG_HXL 0x11
71 #define AK09916REG_HXH 0x12
72 #define AK09916REG_HYL 0x13
73 #define AK09916REG_HYH 0x14
74 #define AK09916REG_HZL 0x15
75 #define AK09916REG_HZH 0x16
76 #define AK09916REG_ST1 0x10
77 #define AK09916REG_ST2 0x18
78 #define AK09916REG_CNTL2 0x31
79 #define AK09916REG_CNTL3 0x32
80 
81 
82 #define AK09916_CNTL2_POWERDOWN_MODE 0x00
83 #define AK09916_CNTL2_SINGLE_MODE 0x01 /* default */
84 #define AK09916_CNTL2_CONTINOUS_MODE_10HZ 0x02
85 #define AK09916_CNTL2_CONTINOUS_MODE_20HZ 0x04
86 #define AK09916_CNTL2_CONTINOUS_MODE_50HZ 0x06
87 #define AK09916_CNTL2_CONTINOUS_MODE_100HZ 0x08
88 #define AK09916_CNTL2_SELFTEST_MODE 0x10
89 #define AK09916_CNTL3_SRST 0x01
90 #define AK09916_ST1_DRDY 0x01
91 #define AK09916_ST1_DOR 0x02
92 
93 class MPU9250;
94 
95 #pragma pack(push, 1)
96 struct ak8963_regs {
97  uint8_t st1;
98  int16_t x;
99  int16_t y;
100  int16_t z;
101  uint8_t st2;
102 };
103 #pragma pack(pop)
104 
105 extern device::Device *AK8963_I2C_interface(int bus);
106 
107 typedef device::Device *(*MPU9250_mag_constructor)(int, bool);
108 
109 /**
110  * Helper class implementing the magnetometer driver node.
111  */
113 {
114 public:
115  MPU9250_mag(MPU9250 *parent, device::Device *interface, enum Rotation rotation);
116  ~MPU9250_mag();
117 
118  void set_passthrough(uint8_t reg, uint8_t size, uint8_t *out = NULL);
119  void passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size);
120  void passthrough_write(uint8_t reg, uint8_t val);
121  void read_block(uint8_t reg, uint8_t *val, uint8_t count);
122 
123  int ak8963_reset();
124  int ak8963_setup();
125  int ak8963_setup_master_i2c();
126  bool ak8963_check_id(uint8_t &id);
127  bool ak8963_read_adjustments();
128 
129  void print_status() { _px4_mag.print_status(); }
130 
131 protected:
133 
134  friend class MPU9250;
135 
136  void measure();
137  void _measure(hrt_abstime timestamp_sample, ak8963_regs data);
138 
139  uint8_t read_reg(unsigned reg);
140  void write_reg(unsigned reg, uint8_t value);
141 
142  bool is_passthrough() { return _interface == nullptr; }
143 
144 private:
146 
148 
149  bool _mag_reading_data{false};
150 
154 
155 };
device::Device * _interface
Definition: MPU9250_mag.h:132
static constexpr float MPU9250_MAG_RANGE_GA
Definition: MPU9250_mag.h:41
uint8_t read_reg(unsigned reg, uint32_t speed=MPU9250_LOW_BUS_SPEED)
Read a register from the mpu.
Definition: mpu9250.cpp:382
uint8_t st1
Definition: MPU9250_mag.h:97
device::Device * AK8963_I2C_interface(int bus)
int16_t y
Definition: MPU9250_mag.h:99
perf_counter_t _mag_errors
Definition: MPU9250_mag.h:153
int16_t x
Definition: MPU9250_mag.h:98
Definitions for the generic base classes in the device framework.
MPU9250 * _parent
Definition: MPU9250_mag.h:147
perf_counter_t _mag_overruns
Definition: MPU9250_mag.h:151
Header common to all counters.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t * data
Definition: dataman.cpp:149
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Helper class implementing the magnetometer driver node.
Definition: MPU9250_mag.h:112
void print_status()
Definition: MPU9250_mag.h:129
perf_counter_t _mag_overflows
Definition: MPU9250_mag.h:152
void measure()
Fetch measurements from the sensor and update the report buffers.
Definition: mpu9250.cpp:619
uint8_t st2
Definition: MPU9250_mag.h:101
bool is_passthrough()
Definition: MPU9250_mag.h:142
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
PX4Magnetometer _px4_mag
Definition: MPU9250_mag.h:145
void write_reg(unsigned reg, uint8_t value)
Write a register in the mpu.
Definition: mpu9250.cpp:413
int16_t z
Definition: MPU9250_mag.h:100
Performance measuring tools.