PX4 Firmware
PX4 Autopilot Software http://px4.io
ICM20948_mag.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2016 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 ICM20948_MAG_RANGE_GA{1.5e-3f};
42 
43 #define ICM20948_AK09916_SAMPLE_RATE 100
44 
45 #define AK09916_I2C_ADDR 0x0C
46 #define AK09916_DEVICE_ID 0x48
47 
48 #define AK09916REG_WIA 0x00
49 #define AK09916REG_CNTL1 0x0A
50 #define AK09916REG_ASAX 0x10
51 
52 #define AK09916_SINGLE_MEAS_MODE 0x01
53 #define AK09916_CONTINUOUS_MODE1 0x02
54 #define AK09916_CONTINUOUS_MODE2 0x06
55 #define AK09916_POWERDOWN_MODE 0x00
56 #define AK09916_SELFTEST_MODE 0x08
57 #define AK09916_FUZE_MODE 0x0F
58 #define AK09916_16BIT_ADC 0x10
59 #define AK09916_14BIT_ADC 0x00
60 #define AK09916_RESET 0x01
61 #define AK09916_HOFL 0x08
62 
63 /* ak09916 deviating register addresses and bit definitions */
64 
65 #define AK09916_DEVICE_ID_A 0x48 // same as AK09916
66 #define AK09916_DEVICE_ID_B 0x09 // additional ID byte ("INFO" on AK9063 without content specification.)
67 
68 #define AK09916REG_HXL 0x11
69 #define AK09916REG_HXH 0x12
70 #define AK09916REG_HYL 0x13
71 #define AK09916REG_HYH 0x14
72 #define AK09916REG_HZL 0x15
73 #define AK09916REG_HZH 0x16
74 #define AK09916REG_ST1 0x10
75 #define AK09916REG_ST2 0x18
76 #define AK09916REG_CNTL2 0x31
77 #define AK09916REG_CNTL3 0x32
78 
79 
80 #define AK09916_CNTL2_POWERDOWN_MODE 0x00
81 #define AK09916_CNTL2_SINGLE_MODE 0x01 /* default */
82 #define AK09916_CNTL2_CONTINOUS_MODE_10HZ 0x02
83 #define AK09916_CNTL2_CONTINOUS_MODE_20HZ 0x04
84 #define AK09916_CNTL2_CONTINOUS_MODE_50HZ 0x06
85 #define AK09916_CNTL2_CONTINOUS_MODE_100HZ 0x08
86 #define AK09916_CNTL2_SELFTEST_MODE 0x10
87 #define AK09916_CNTL3_SRST 0x01
88 #define AK09916_ST1_DRDY 0x01
89 #define AK09916_ST1_DOR 0x02
90 
91 class ICM20948;
92 
93 #pragma pack(push, 1)
94 struct ak09916_regs {
95  uint8_t st1;
96  int16_t x;
97  int16_t y;
98  int16_t z;
99  uint8_t tmps;
100  uint8_t st2;
101 };
102 #pragma pack(pop)
103 
104 extern device::Device *AK09916_I2C_interface(int bus);
105 
106 typedef device::Device *(*ICM20948_mag_constructor)(int, bool);
107 
108 /**
109  * Helper class implementing the magnetometer driver node.
110  */
112 {
113 public:
114  ICM20948_mag(ICM20948 *parent, device::Device *interface, enum Rotation rotation);
115  ~ICM20948_mag();
116 
117  void set_passthrough(uint8_t reg, uint8_t size, uint8_t *out = NULL);
118  void passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size);
119  void passthrough_write(uint8_t reg, uint8_t val);
120  void read_block(uint8_t reg, uint8_t *val, uint8_t count);
121 
122  int ak09916_reset();
123  int ak09916_setup();
124  int ak09916_setup_master_i2c();
125  bool ak09916_check_id(uint8_t &id);
126  bool ak09916_read_adjustments();
127 
128  void print_status() { _px4_mag.print_status(); }
129 
130 protected:
132 
133  friend class ICM20948;
134 
135  void measure();
136  void _measure(hrt_abstime timestamp_sample, ak09916_regs data);
137 
138  uint8_t read_reg(unsigned reg);
139  void write_reg(unsigned reg, uint8_t value);
140 
141  bool is_passthrough() { return _interface == nullptr; }
142 
143 private:
145 
147 
148  bool _mag_reading_data{false};
149 
153 
154 };
void print_status()
Definition: ICM20948_mag.h:128
bool is_passthrough()
Definition: ICM20948_mag.h:141
perf_counter_t _mag_errors
Definition: ICM20948_mag.h:152
device::Device * _interface
Definition: ICM20948_mag.h:131
static constexpr float ICM20948_MAG_RANGE_GA
Definition: ICM20948_mag.h:41
Helper class implementing the magnetometer driver node.
Definition: ICM20948_mag.h:111
PX4Magnetometer _px4_mag
Definition: ICM20948_mag.h:144
uint8_t tmps
Definition: ICM20948_mag.h:99
Definitions for the generic base classes in the device framework.
void write_reg(unsigned reg, uint8_t value)
Write a register in the mpu.
Definition: icm20948.cpp:524
uint8_t read_reg(unsigned reg, uint32_t speed=ICM20948_LOW_BUS_SPEED)
Read a register from the mpu.
Definition: icm20948.cpp:490
device::Device * AK09916_I2C_interface(int bus)
Header common to all counters.
void measure()
Fetch measurements from the sensor and update the report buffers.
Definition: icm20948.cpp:731
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
perf_counter_t _mag_overruns
Definition: ICM20948_mag.h:150
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
ICM20948 * _parent
Definition: ICM20948_mag.h:146
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
uint8_t st1
Definition: ICM20948_mag.h:95
perf_counter_t _mag_overflows
Definition: ICM20948_mag.h:151
Performance measuring tools.