APM:Libraries
AP_InertialSensor_RST.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  IMU driver for Robsense PhenixPro Devkit board including i3g4250d and iis328dq
17  */
18 #include <AP_HAL/AP_HAL.h>
19 
20 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ
21 #include "AP_InertialSensor_RST.h"
22 #include <AP_Math/AP_Math.h>
23 
24 #include <inttypes.h>
25 #include <utility>
26 #include <math.h>
27 #include <stdio.h>
28 
29 const extern AP_HAL::HAL &hal;
30 
31 #define ADDR_INCREMENT (1<<6)
32 
33 /************************************iis328dq register addresses *******************************************/
34 #define ACCEL_WHO_AM_I 0x0F
35 #define ACCEL_WHO_I_AM 0x32
36 
37 #define ACCEL_CTRL_REG1 0x20
38 /* keep lowpass low to avoid noise issues */
39 #define RATE_50HZ_LP_37HZ (0<<4) | (0<<3)
40 #define RATE_100HZ_LP_74HZ (0<<4) | (1<<3)
41 #define RATE_400HZ_LP_292HZ (1<<4) | (0<<3)
42 #define RATE_1000HZ_LP_780HZ (1<<4) | (1<<3)
43 
44 #define ACCEL_CTRL_REG2 0x21
45 #define ACCEL_CTRL_REG3 0x22
46 #define ACCEL_CTRL_REG4 0x23
47 
48 #define ACCEL_CTRL_REG5 0x24
49 #define ACCEL_HP_FILTER_RESETE 0x25
50 #define ACCEL_OUT_REFERENCE 0x26
51 #define ACCEL_STATUS_REG 0x27
52 #define ACCEL_OUT_X_L 0x28
53 #define ACCEL_OUT_X_H 0x29
54 #define ACCEL_OUT_Y_L 0x2A
55 #define ACCEL_OUT_Y_H 0x2B
56 #define ACCEL_OUT_Z_L 0x2C
57 #define ACCEL_OUT_Z_H 0x2D
58 #define ACCEL_INT1_CFG 0x30
59 #define ACCEL_INT1_SRC 0x31
60 #define ACCEL_INT1_TSH 0x32
61 #define ACCEL_INT1_DURATION 0x33
62 #define ACCEL_INT2_CFG 0x34
63 #define ACCEL_INT2_SRC 0x35
64 #define ACCEL_INT2_TSH 0x36
65 #define ACCEL_INT2_DURATION 0x37
66 
67 
68 /* Internal configuration values */
69 #define ACCEL_REG1_POWER_NORMAL ((0<<7) | (0<<6) | (1<<5))
70 #define ACCEL_REG1_Z_ENABLE (1<<2)
71 #define ACCEL_REG1_Y_ENABLE (1<<1)
72 #define ACCEL_REG1_X_ENABLE (1<<0)
73 
74 #define ACCEL_REG4_BDU (1<<7)
75 #define ACCEL_REG4_BLE (1<<6)
76 #define ACCEL_REG4_FULL_SCALE_BITS ((1<<5) | (1<<4))
77 #define ACCEL_REG4_FULL_SCALE_2G ((0<<5) | (0<<4))
78 #define ACCEL_REG4_FULL_SCALE_4G ((0<<5) | (1<<4))
79 #define ACCEL_REG4_FULL_SCALE_8G ((1<<5) | (1<<4))
80 
81 #define ACCEL_STATUS_ZYXOR (1<<7)
82 #define ACCEL_STATUS_ZOR (1<<6)
83 #define ACCEL_STATUS_YOR (1<<5)
84 #define ACCEL_STATUS_XOR (1<<4)
85 #define ACCEL_STATUS_ZYXDA (1<<3)
86 #define ACCEL_STATUS_ZDA (1<<2)
87 #define ACCEL_STATUS_YDA (1<<1)
88 #define ACCEL_STATUS_XDA (1<<0)
89 
90 #define ACCEL_DEFAULT_RANGE_G 8
91 #define ACCEL_DEFAULT_RATE 1000
92 #define ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 780
93 #define ACCEL_ONE_G 9.80665f
94 
95 /************************************i3g4250d register addresses *******************************************/
96 #define GYRO_WHO_AM_I 0x0F
97 #define GYRO_WHO_I_AM 0xD3
98 
99 #define GYRO_CTRL_REG1 0x20
100 /* keep lowpass low to avoid noise issues */
101 #define RATE_100HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
102 #define RATE_200HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
103 #define RATE_200HZ_LP_50HZ ((0<<7) | (1<<6) | (1<<5) | (0<<4))
104 #define RATE_200HZ_LP_70HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
105 #define RATE_400HZ_LP_20HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
106 #define RATE_400HZ_LP_25HZ ((1<<7) | (0<<6) | (0<<5) | (1<<4))
107 #define RATE_400HZ_LP_50HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
108 #define RATE_400HZ_LP_100HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
109 #define RATE_800HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4))
110 #define RATE_800HZ_LP_35HZ ((1<<7) | (1<<6) | (0<<5) | (1<<4))
111 #define RATE_800HZ_LP_50HZ ((1<<7) | (1<<6) | (1<<5) | (0<<4))
112 #define RATE_800HZ_LP_100HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
113 
114 #define GYRO_CTRL_REG2 0x21
115 #define GYRO_CTRL_REG3 0x22
116 #define GYRO_CTRL_REG4 0x23
117 #define RANGE_250DPS (0<<4)
118 #define RANGE_500DPS (1<<4)
119 #define RANGE_2000DPS (3<<4)
120 
121 #define GYRO_CTRL_REG5 0x24
122 #define GYRO_REFERENCE 0x25
123 #define GYRO_OUT_TEMP 0x26
124 #define GYRO_STATUS_REG 0x27
125 #define GYRO_OUT_X_L 0x28
126 #define GYRO_OUT_X_H 0x29
127 #define GYRO_OUT_Y_L 0x2A
128 #define GYRO_OUT_Y_H 0x2B
129 #define GYRO_OUT_Z_L 0x2C
130 #define GYRO_OUT_Z_H 0x2D
131 #define GYRO_FIFO_CTRL_REG 0x2E
132 #define GYRO_FIFO_SRC_REG 0x2F
133 #define GYRO_INT1_CFG 0x30
134 #define GYRO_INT1_SRC 0x31
135 #define GYRO_INT1_TSH_XH 0x32
136 #define GYRO_INT1_TSH_XL 0x33
137 #define GYRO_INT1_TSH_YH 0x34
138 #define GYRO_INT1_TSH_YL 0x35
139 #define GYRO_INT1_TSH_ZH 0x36
140 #define GYRO_INT1_TSH_ZL 0x37
141 #define GYRO_INT1_DURATION 0x38
142 #define GYRO_LOW_ODR 0x39
143 
144 
145 /* Internal configuration values */
146 #define GYRO_REG1_POWER_NORMAL (1<<3)
147 #define GYRO_REG1_Z_ENABLE (1<<2)
148 #define GYRO_REG1_Y_ENABLE (1<<1)
149 #define GYRO_REG1_X_ENABLE (1<<0)
150 
151 #define GYRO_REG4_BLE (1<<6)
152 
153 #define GYRO_REG5_FIFO_ENABLE (1<<6)
154 #define GYRO_REG5_REBOOT_MEMORY (1<<7)
155 
156 #define GYRO_STATUS_ZYXOR (1<<7)
157 #define GYRO_STATUS_ZOR (1<<6)
158 #define GYRO_STATUS_YOR (1<<5)
159 #define GYRO_STATUS_XOR (1<<4)
160 #define GYRO_STATUS_ZYXDA (1<<3)
161 #define GYRO_STATUS_ZDA (1<<2)
162 #define GYRO_STATUS_YDA (1<<1)
163 #define GYRO_STATUS_XDA (1<<0)
164 
165 #define GYRO_FIFO_CTRL_BYPASS_MODE (0<<5)
166 #define GYRO_FIFO_CTRL_FIFO_MODE (1<<5)
167 #define GYRO_FIFO_CTRL_STREAM_MODE (1<<6)
168 #define GYRO_FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
169 #define GYRO_FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
170 
171 //data output frequency
172 #define GYRO_DEFAULT_RATE 800
173 #define GYRO_DEFAULT_RANGE_DPS 2000
174 #define GYRO_DEFAULT_FILTER_FREQ 35
175 #define GYRO_TEMP_OFFSET_CELSIUS 40
176 
177 
178 // constructor
182  enum Rotation rotation_g,
183  enum Rotation rotation_a)
185  , _dev_gyro(std::move(dev_gyro))
186  , _dev_accel(std::move(dev_accel))
187  , _rotation_g(rotation_g)
188  , _rotation_a(rotation_a)
189 {
190 }
191 
193 {
194 }
195 
196 /*
197  detect the sensor
198  */
202  enum Rotation rotation_g,
203  enum Rotation rotation_a)
204 {
205  if (!dev_gyro && !dev_accel) {
206  return nullptr;
207  }
208  AP_InertialSensor_RST *sensor
209  = new AP_InertialSensor_RST(imu, std::move(dev_gyro), std::move(dev_accel), rotation_g, rotation_a);
210  if (!sensor || !sensor->_init_sensor()) {
211  delete sensor;
212  return nullptr;
213  }
214 
215  return sensor;
216 }
217 
218 /*
219  * init gyro
220  */
222 {
223  uint8_t whoami;
224 
226  return false;
227  }
228 
229  // set flag for reading registers
230  _dev_gyro->set_read_flag(0x80);
231 
233 
234  _dev_gyro->read_registers(GYRO_WHO_AM_I, &whoami, sizeof(whoami));
235  if (whoami != GYRO_WHO_I_AM) {
236  hal.console->printf("RST: unexpected gyro WHOAMI 0x%x\n", (unsigned)whoami);
237  printf("RST: unexpected gyro WHOAMI 0x%x\n", (unsigned)whoami);
238  goto fail_whoami;
239  }
240 
241  printf("detect i3g4250d\n");
242 
243  //enter power-down mode first
245 
246  hal.scheduler->delay(100);
247 
252 
253  /* disable high-pass filters */
255 
256  /* DRDY disable */
259 
260  /* disable wake-on-interrupt */
262 
263  /* disable FIFO. This makes things simpler and ensures we
264  * aren't getting stale data. It means we must run the hrt
265  * callback fast enough to not miss data. */
267 
268  _gyro_scale = 70e-3f / 180.0f * M_PI;
269 
270  hal.scheduler->delay(100);
271 
273 
274  return true;
275 
276 fail_whoami:
278  return false;
279 }
280 
281 /*
282  * init accel
283  */
285 {
286  uint8_t whoami;
287 
289  return false;
290  }
291 
293 
294  _dev_accel->set_read_flag(0x80);
295 
296  _dev_accel->read_registers(ACCEL_WHO_AM_I, &whoami, sizeof(whoami));
297  if (whoami != ACCEL_WHO_I_AM) {
298  hal.console->printf("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami);
299  printf("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami);
300  goto fail_whoami;
301  }
302 
307 
308  /* disable high-pass filters */
310 
311  /* DRDY enable */
315 
316  _accel_scale = 0.244e-3f * ACCEL_ONE_G;
317 
319 
320  return true;
321 
322 fail_whoami:
324  return false;
325 
326 
327 }
328 
330 {
331  if (!_init_gyro() || !_init_accel()) {
332  return false;
333  }
334 
335  return true;
336 }
337 
338 /*
339  startup the sensor
340  */
342 {
345 
348 
349  // start the timer process to read samples
352 }
353 
354 /*
355  copy filtered data to the frontend
356  */
358 {
361 
362  return true;
363 }
364 
365 // Accumulate values from gyros
367 {
368  Vector3f gyro;
369  uint8_t status = 0;
370  int16_t raw_data[3];
371 
372  _dev_gyro->read_registers(GYRO_STATUS_REG, &status, sizeof(status));
373 
374  if ((status & GYRO_STATUS_ZYXDA) == 0) {
375  return;
376  }
377 
378  if (_dev_gyro->read_registers(GYRO_OUT_X_L | ADDR_INCREMENT, (uint8_t *)raw_data, sizeof(raw_data))) {
379  gyro = Vector3f(raw_data[0], raw_data[1], raw_data[2]);
380  gyro *= _gyro_scale;
383  }
384 }
385 
386 // Accumulate values from accels
388 {
389  Vector3f accel;
390  uint8_t status = 0;
391  int16_t raw_data[3];
392 
393  _dev_accel->read_registers(ACCEL_STATUS_REG, &status, sizeof(status));
394 
395  if ((status & ACCEL_STATUS_ZYXDA) == 0) {
396  return;
397  }
398 
399  if (_dev_accel->read_registers(ACCEL_OUT_X_L | ADDR_INCREMENT, (uint8_t *)raw_data, sizeof(raw_data))) {
400  accel = Vector3f(raw_data[0], raw_data[1], raw_data[2]);
401  accel *= _accel_scale;
404  }
405 }
406 
407 #endif
#define ACCEL_REG4_FULL_SCALE_8G
int printf(const char *fmt,...)
Definition: stdio.c:113
void set_gyro_orientation(uint8_t instance, enum Rotation rotation)
#define RATE_800HZ_LP_50HZ
Vector3< float > Vector3f
Definition: vector3.h:246
#define ACCEL_REG1_Z_ENABLE
#define ACCEL_CTRL_REG4
#define ACCEL_REG1_Y_ENABLE
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define GYRO_STATUS_ZYXDA
#define GYRO_WHO_AM_I
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define ACCEL_REG1_POWER_NORMAL
#define ADDR_INCREMENT
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define GYRO_REG1_Y_ENABLE
#define GYRO_REG1_X_ENABLE
#define GYRO_FIFO_CTRL_REG
#define GYRO_WHO_I_AM
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define GYRO_REG1_POWER_NORMAL
#define GYRO_CTRL_REG1
Rotation
Definition: rotations.h:27
#define ACCEL_CTRL_REG2
uint32_t get_bus_id_devtype(uint8_t devtype)
Definition: Device.h:255
#define ACCEL_REG4_BDU
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_accel
virtual void delay(uint16_t ms)=0
#define ACCEL_WHO_AM_I
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
#define ACCEL_OUT_X_L
virtual Semaphore * get_semaphore() override=0
#define f(i)
#define GYRO_OUT_X_L
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
#define ACCEL_CTRL_REG3
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
#define GYRO_REG1_Z_ENABLE
virtual bool give()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_gyro
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
virtual bool set_speed(Device::Speed speed) override=0
#define RATE_1000HZ_LP_780HZ
#define ACCEL_CTRL_REG1
void set_read_flag(uint8_t flag)
Definition: Device.h:221
void set_accel_orientation(uint8_t instance, enum Rotation rotation)
#define ACCEL_STATUS_ZYXDA
#define GYRO_STATUS_REG
#define GYRO_REG5_FIFO_ENABLE
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a, enum Rotation rotation_g)
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
#define ACCEL_REG1_X_ENABLE
#define M_PI
Definition: definitions.h:10
#define GYRO_CTRL_REG4
#define GYRO_CTRL_REG5
#define GYRO_CTRL_REG3
#define ACCEL_STATUS_REG
#define ACCEL_WHO_I_AM
#define GYRO_CTRL_REG2
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
#define GYRO_FIFO_CTRL_BYPASS_MODE
#define ACCEL_ONE_G
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
AP_InertialSensor_RST(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a, enum Rotation rotation_g)
#define RANGE_2000DPS