APM:Libraries
AP_Compass_IST8310.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Emlid Ltd. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  *
17  * Driver by Georgii Staroselskii, Sep 2016
18  */
19 #include "AP_Compass_IST8310.h"
20 
21 #include <stdio.h>
22 #include <utility>
23 
24 #include <AP_HAL/AP_HAL.h>
26 #include <AP_Math/AP_Math.h>
27 
28 #define WAI_REG 0x0
29 #define DEVICE_ID 0x10
30 
31 #define OUTPUT_X_L_REG 0x3
32 #define OUTPUT_X_H_REG 0x4
33 #define OUTPUT_Y_L_REG 0x5
34 #define OUTPUT_Y_H_REG 0x6
35 #define OUTPUT_Z_L_REG 0x7
36 #define OUTPUT_Z_H_REG 0x8
37 
38 #define CNTL1_REG 0xA
39 #define CNTL1_VAL_SINGLE_MEASUREMENT_MODE 0x1
40 
41 #define CNTL2_REG 0xB
42 #define CNTL2_VAL_SRST 1
43 
44 #define AVGCNTL_REG 0x41
45 #define AVGCNTL_VAL_XZ_0 (0)
46 #define AVGCNTL_VAL_XZ_2 (1)
47 #define AVGCNTL_VAL_XZ_4 (2)
48 #define AVGCNTL_VAL_XZ_8 (3)
49 #define AVGCNTL_VAL_XZ_16 (4)
50 #define AVGCNTL_VAL_Y_0 (0 << 3)
51 #define AVGCNTL_VAL_Y_2 (1 << 3)
52 #define AVGCNTL_VAL_Y_4 (2 << 3)
53 #define AVGCNTL_VAL_Y_8 (3 << 3)
54 #define AVGCNTL_VAL_Y_16 (4 << 3)
55 
56 #define PDCNTL_REG 0x42
57 #define PDCNTL_VAL_PULSE_DURATION_NORMAL 0xC0
58 
59 #define SAMPLING_PERIOD_USEC (10 * AP_USEC_PER_MSEC)
60 
61 /*
62  * FSR:
63  * x, y: +- 1600 µT
64  * z: +- 2500 µT
65  *
66  * Resolution according to datasheet is 0.3µT/LSB
67  */
68 #define IST8310_RESOLUTION 0.3
69 
70 static const int16_t IST8310_MAX_VAL_XY = (1600 / IST8310_RESOLUTION) + 1;
71 static const int16_t IST8310_MIN_VAL_XY = -IST8310_MAX_VAL_XY;
72 static const int16_t IST8310_MAX_VAL_Z = (2500 / IST8310_RESOLUTION) + 1;
73 static const int16_t IST8310_MIN_VAL_Z = -IST8310_MAX_VAL_Z;
74 
75 
76 extern const AP_HAL::HAL &hal;
77 
80  bool force_external,
81  enum Rotation rotation)
82 {
83  if (!dev) {
84  return nullptr;
85  }
86 
87  AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(compass, std::move(dev), force_external, rotation);
88  if (!sensor || !sensor->init()) {
89  delete sensor;
90  return nullptr;
91  }
92 
93  return sensor;
94 }
95 
98  bool force_external,
99  enum Rotation rotation)
100  : AP_Compass_Backend(compass)
101  , _dev(std::move(dev))
102  , _rotation(rotation)
103  , _force_external(force_external)
104 {
105 }
106 
108 {
109  uint8_t reset_count = 0;
110 
112  return false;
113  }
114 
115  // high retries for init
116  _dev->set_retries(10);
117 
118  uint8_t whoami;
119  if (!_dev->read_registers(WAI_REG, &whoami, 1) ||
120  whoami != DEVICE_ID) {
121  // not an IST8310
122  goto fail;
123  }
124 
125  for (; reset_count < 5; reset_count++) {
127  hal.scheduler->delay(10);
128  continue;
129  }
130 
131  hal.scheduler->delay(10);
132 
133  uint8_t cntl2 = 0xFF;
134  if (_dev->read_registers(CNTL2_REG, &cntl2, 1) &&
135  (cntl2 & 0x01) == 0) {
136  break;
137  }
138  }
139 
140  if (reset_count == 5) {
141  printf("IST8310: failed to reset device\n");
142  goto fail;
143  }
144 
147  printf("IST8310: found device but could not set it up\n");
148  goto fail;
149  }
150 
151  // lower retries for run
152  _dev->set_retries(3);
153 
154  // start state machine: request a sample
156 
157  _dev->get_semaphore()->give();
158 
160 
161  printf("%s found on bus %u id %u address 0x%02x\n", name,
163 
165 
168 
169  if (_force_external) {
170  set_external(_instance, true);
171  }
172 
175 
176  _perf_xfer_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8310_xfer_err");
177  _perf_bad_data = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8310_bad_data");
178 
179  return true;
180 
181 fail:
182  _dev->get_semaphore()->give();
183  return false;
184 }
185 
187 {
190  _ignore_next_sample = true;
191  }
192 }
193 
195 {
196  if (_ignore_next_sample) {
197  _ignore_next_sample = false;
199  return;
200  }
201 
202  struct PACKED {
203  le16_t rx;
204  le16_t ry;
205  le16_t rz;
206  } buffer;
207 
208  bool ret = _dev->read_registers(OUTPUT_X_L_REG, (uint8_t *) &buffer, sizeof(buffer));
209  if (!ret) {
211  return;
212  }
213 
215 
216  /* same period, but start counting from now */
218 
219  auto x = static_cast<int16_t>(le16toh(buffer.rx));
220  auto y = static_cast<int16_t>(le16toh(buffer.ry));
221  auto z = static_cast<int16_t>(le16toh(buffer.rz));
222 
223  /*
224  * Check if value makes sense according to the FSR and Resolution of
225  * this sensor, discarding outliers
226  */
231  return;
232  }
233 
234  // flip Z to conform to right-hand rule convention
235  z = -z;
236 
237  /* Resolution: 0.3 µT/LSB - already convert to milligauss */
238  Vector3f field = Vector3f{x * 3.0f, y * 3.0f, z * 3.0f};
239 
240  /* rotate raw_field from sensor frame to body frame */
241  rotate_field(field, _instance);
242 
243  /* publish raw_field (uncorrected point sample) for calibration use */
245 
246  /* correct raw_field for known errors */
247  correct_field(field, _instance);
248 
250  _accum += field;
251  _accum_count++;
252  _sem->give();
253  }
254 }
255 
257 {
258  if (!_sem->take_nonblocking()) {
259  return;
260  }
261 
262  if (_accum_count == 0) {
263  _sem->give();
264  return;
265  }
266 
267  Vector3f field(_accum);
268  field /= _accum_count;
269 
271 
272  _accum.zero();
273  _accum_count = 0;
274 
275  _sem->give();
276 }
int printf(const char *fmt,...)
Definition: stdio.c:113
static const int16_t IST8310_MIN_VAL_XY
void set_external(uint8_t instance, bool external)
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
Definition: Util.h:102
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define OUTPUT_X_L_REG
#define DEVICE_ID
#define CNTL2_VAL_SRST
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
#define SAMPLING_PERIOD_USEC
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
uint32_t get_bus_id(void) const
Definition: Device.h:60
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
#define PDCNTL_VAL_PULSE_DURATION_NORMAL
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
AP_HAL::Util::perf_counter_t _perf_bad_data
void correct_field(Vector3f &mag, uint8_t i)
uint8_t get_bus_address(void) const
Definition: Device.h:65
AP_HAL::Device::PeriodicHandle _periodic_handle
AP_HAL::Util * util
Definition: HAL.h:115
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
uint8_t bus_num(void) const
Definition: Device.h:55
void fail(const char *why)
Definition: eedump.c:28
static const int16_t IST8310_MIN_VAL_Z
#define AVGCNTL_VAL_Y_16
virtual void delay(uint16_t ms)=0
void set_device_type(uint8_t devtype)
Definition: Device.h:70
#define x(i)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define AVGCNTL_VAL_XZ_16
uint8_t register_compass(void) const
enum Rotation _rotation
static constexpr const char * name
#define PDCNTL_REG
virtual bool adjust_periodic_callback(PeriodicHandle h, uint32_t period_usec)=0
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual bool give()=0
static Compass compass
Definition: AHRS_Test.cpp:20
uint16_t __ap_bitwise le16_t
Definition: sparse-endian.h:35
AP_HAL::Semaphore * _sem
#define CNTL1_VAL_SINGLE_MEASUREMENT_MODE
#define IST8310_RESOLUTION
#define WAI_REG
#define CNTL1_REG
static const int16_t IST8310_MAX_VAL_XY
static const int16_t IST8310_MAX_VAL_Z
void set_rotation(uint8_t instance, enum Rotation rotation)
AP_Compass_IST8310(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
#define CNTL2_REG
#define PACKED
Definition: AP_Common.h:28
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void publish_raw_field(const Vector3f &mag, uint8_t instance)
static uint16_t le16toh(le16_t value)
Definition: sparse-endian.h:79
AP_HAL::Util::perf_counter_t _perf_xfer_err
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define AVGCNTL_REG
virtual void perf_count(perf_counter_t h)
Definition: Util.h:105