APM:Libraries
AP_InertialSensor_PX4.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
3 
5 
6 const extern AP_HAL::HAL& hal;
7 
8 #include <sys/types.h>
9 #include <sys/stat.h>
10 #include <fcntl.h>
11 #include <unistd.h>
12 
13 #include <drivers/drv_accel.h>
14 #include <drivers/drv_gyro.h>
15 #include <drivers/drv_hrt.h>
16 
17 #include <stdio.h>
18 
21 {
22 }
23 
24 /*
25  detect the sensor
26  */
28 {
29  AP_InertialSensor_PX4 *sensor = new AP_InertialSensor_PX4(_imu);
30  if (sensor == nullptr) {
31  return nullptr;
32  }
33  if (!sensor->_init_sensor()) {
34  delete sensor;
35  return nullptr;
36  }
37  return sensor;
38 }
39 
40 /*
41  calculate the right queue depth for a device with the given sensor
42  sample rate
43  */
44 uint8_t AP_InertialSensor_PX4::_queue_depth(uint16_t sensor_sample_rate) const
45 {
46  uint16_t requested_sample_rate = get_sample_rate_hz();
47  uint8_t min_depth = (sensor_sample_rate+requested_sample_rate-1)/requested_sample_rate;
48  // add 5ms more worth of queue to account for possible timing jitter
49  uint8_t ret = min_depth + (5 * sensor_sample_rate) / 1000;
50  return ret;
51 }
52 
54 {
55  // assumes max 3 instances
56  _accel_fd[0] = open(ACCEL_BASE_DEVICE_PATH "0", O_RDONLY);
57  _accel_fd[1] = open(ACCEL_BASE_DEVICE_PATH "1", O_RDONLY);
58  _accel_fd[2] = open(ACCEL_BASE_DEVICE_PATH "2", O_RDONLY);
59  _gyro_fd[0] = open(GYRO_BASE_DEVICE_PATH "0", O_RDONLY);
60  _gyro_fd[1] = open(GYRO_BASE_DEVICE_PATH "1", O_RDONLY);
61  _gyro_fd[2] = open(GYRO_BASE_DEVICE_PATH "2", O_RDONLY);
62 
65  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
66  if (_accel_fd[i] >= 0) {
68  }
69  if (_gyro_fd[i] >= 0) {
70  _num_gyro_instances = i+1;
71  }
72  }
73  if (_num_accel_instances == 0) {
74  return false;
75  }
76  if (_num_gyro_instances == 0) {
77  return false;
78  }
79 
80  for (uint8_t i=0; i<_num_gyro_instances; i++) {
81  int fd = _gyro_fd[i];
82  int devid = (ioctl(fd, DEVIOCGDEVICEID, 0) & 0x00FF0000)>>16;
83 
84  // software LPF off
85  ioctl(fd, GYROIOCSLOWPASS, 0);
86  // 2000dps range
87  ioctl(fd, GYROIOCSRANGE, 2000);
88 
89  switch(devid) {
90  case DRV_GYR_DEVTYPE_MPU6000:
91  case DRV_GYR_DEVTYPE_MPU9250:
92  // hardware LPF off
93  ioctl(fd, GYROIOCSHWLOWPASS, 256);
94  // khz sampling
95  ioctl(fd, GYROIOCSSAMPLERATE, 1000);
96  // set queue depth
97  ioctl(fd, SENSORIOCSQUEUEDEPTH, _queue_depth(1000));
98  break;
99  case DRV_GYR_DEVTYPE_L3GD20:
100  // hardware LPF as high as possible
101  ioctl(fd, GYROIOCSHWLOWPASS, 100);
102  // ~khz sampling
103  ioctl(fd, GYROIOCSSAMPLERATE, 800);
104  // 10ms queue depth
105  ioctl(fd, SENSORIOCSQUEUEDEPTH, _queue_depth(800));
106  break;
107  default:
108  break;
109  }
110  // calculate gyro sample time
111  int samplerate = ioctl(fd, GYROIOCGSAMPLERATE, 0);
112  if (samplerate < 100 || samplerate > 10000) {
113  AP_HAL::panic("Invalid gyro sample rate");
114  }
115  _gyro_instance[i] = _imu.register_gyro(samplerate, ioctl(fd, DEVIOCGDEVICEID, 0));
116  _gyro_sample_time[i] = 1.0f / samplerate;
117  }
118 
119  for (uint8_t i=0; i<_num_accel_instances; i++) {
120  int fd = _accel_fd[i];
121  int devid = (ioctl(fd, DEVIOCGDEVICEID, 0) & 0x00FF0000)>>16;
122 
123  // software LPF off
124  ioctl(fd, ACCELIOCSLOWPASS, 0);
125  // 16g range
126  ioctl(fd, ACCELIOCSRANGE, 16);
127 
128  switch(devid) {
129  case DRV_ACC_DEVTYPE_MPU6000:
130  case DRV_ACC_DEVTYPE_MPU9250:
131  // hardware LPF off
132  ioctl(fd, ACCELIOCSHWLOWPASS, 256);
133  // khz sampling
134  ioctl(fd, ACCELIOCSSAMPLERATE, 1000);
135  // 10ms queue depth
136  ioctl(fd, SENSORIOCSQUEUEDEPTH, _queue_depth(1000));
137  break;
138  case DRV_ACC_DEVTYPE_LSM303D:
139  // hardware LPF to ~1/10th sample rate for antialiasing
140  ioctl(fd, ACCELIOCSHWLOWPASS, 194);
141  // ~khz sampling
142  ioctl(fd, ACCELIOCSSAMPLERATE, 1600);
143  ioctl(fd,SENSORIOCSPOLLRATE, 1600);
144  // 10ms queue depth
145  ioctl(fd, SENSORIOCSQUEUEDEPTH, _queue_depth(1600));
146  break;
147  default:
148  break;
149  }
150  // calculate accel sample time
151  int samplerate = ioctl(fd, ACCELIOCGSAMPLERATE, 0);
152  if (samplerate < 100 || samplerate > 10000) {
153  AP_HAL::panic("Invalid accel sample rate");
154  }
155  _accel_instance[i] = _imu.register_accel(samplerate, ioctl(fd, DEVIOCGDEVICEID, 0));
156  _accel_sample_time[i] = 1.0f / samplerate;
157  }
158 
159  return true;
160 }
161 
163 {
164  // get the latest sample from the sensor drivers
165  _get_sample();
166 
167  for (uint8_t k=0; k<_num_accel_instances; k++) {
169  }
170 
171  for (uint8_t k=0; k<_num_gyro_instances; k++) {
173  }
174 
175  return true;
176 }
177 
178 void AP_InertialSensor_PX4::_new_accel_sample(uint8_t i, accel_report &accel_report)
179 {
180  Vector3f accel = Vector3f(accel_report.x, accel_report.y, accel_report.z);
181  uint8_t frontend_instance = _accel_instance[i];
182 
183  // apply corrections
184  _rotate_and_correct_accel(frontend_instance, accel);
185  _notify_new_accel_raw_sample(frontend_instance, accel, accel_report.timestamp);
186 
187  // save last timestamp
188  _last_accel_timestamp[i] = accel_report.timestamp;
189 
190  // report error count
191  _set_accel_error_count(frontend_instance, accel_report.error_count);
192 
193  // publish a temperature (for logging purposed only)
194  _publish_temperature(frontend_instance, accel_report.temperature);
195 
196 #ifdef AP_INERTIALSENSOR_PX4_DEBUG
197  // get time since last sample
198  float dt = _accel_sample_time[i];
199 
200  _accel_dt_max[i] = MAX(_accel_dt_max[i],dt);
201 
202  _accel_meas_count[i] ++;
203 
204  if(_accel_meas_count[i] >= 10000) {
205  uint32_t tnow = AP_HAL::micros();
206 
207  ::printf("a%d %.2f Hz max %.8f s\n", frontend_instance, 10000.0f/((tnow-_accel_meas_count_start_us[i])*1.0e-6f),_accel_dt_max[i]);
208 
209  _accel_meas_count_start_us[i] = tnow;
210  _accel_meas_count[i] = 0;
211  _accel_dt_max[i] = 0;
212  }
213 #endif // AP_INERTIALSENSOR_PX4_DEBUG
214 }
215 
216 void AP_InertialSensor_PX4::_new_gyro_sample(uint8_t i, gyro_report &gyro_report)
217 {
218  Vector3f gyro = Vector3f(gyro_report.x, gyro_report.y, gyro_report.z);
219  uint8_t frontend_instance = _gyro_instance[i];
220 
221  // apply corrections
222  _rotate_and_correct_gyro(frontend_instance, gyro);
223  _notify_new_gyro_raw_sample(frontend_instance, gyro, gyro_report.timestamp);
224 
225  // save last timestamp
226  _last_gyro_timestamp[i] = gyro_report.timestamp;
227 
228  // report error count
229  _set_gyro_error_count(_gyro_instance[i], gyro_report.error_count);
230 
231 #ifdef AP_INERTIALSENSOR_PX4_DEBUG
232  // get time since last sample
233  float dt = _gyro_sample_time[i];
234 
235  _gyro_dt_max[i] = MAX(_gyro_dt_max[i],dt);
236 
237  _gyro_meas_count[i] ++;
238 
239  if(_gyro_meas_count[i] >= 10000) {
240  uint32_t tnow = AP_HAL::micros();
241 
242  ::printf("g%d %.2f Hz max %.8f s\n", frontend_instance, 10000.0f/((tnow-_gyro_meas_count_start_us[i])*1.0e-6f), _gyro_dt_max[i]);
243 
244  _gyro_meas_count_start_us[i] = tnow;
245  _gyro_meas_count[i] = 0;
246  _gyro_dt_max[i] = 0;
247  }
248 #endif // AP_INERTIALSENSOR_PX4_DEBUG
249 }
250 
252 {
253  for (uint8_t i=0; i<MAX(_num_accel_instances,_num_gyro_instances);i++) {
254  struct accel_report accel_report;
255  struct gyro_report gyro_report;
256 
257  bool gyro_valid = _get_gyro_sample(i,gyro_report);
258  bool accel_valid = _get_accel_sample(i,accel_report);
259 
260  while(gyro_valid || accel_valid) {
261  // interleave accel and gyro samples by time - this will allow sculling corrections later
262  // check the next gyro measurement to see if it needs to be integrated first
263  if(gyro_valid && accel_valid && gyro_report.timestamp <= accel_report.timestamp) {
264  _new_gyro_sample(i,gyro_report);
265  gyro_valid = _get_gyro_sample(i,gyro_report);
266  continue;
267  }
268  // if not, try to integrate an accelerometer sample
269  if(accel_valid) {
270  _new_accel_sample(i,accel_report);
271  accel_valid = _get_accel_sample(i,accel_report);
272  continue;
273  }
274  // if not, we've only got gyro samples left in the buffer
275  if(gyro_valid) {
276  _new_gyro_sample(i,gyro_report);
277  gyro_valid = _get_gyro_sample(i,gyro_report);
278  }
279  }
280  }
281 }
282 
283 bool AP_InertialSensor_PX4::_get_accel_sample(uint8_t i, struct accel_report &accel_report)
284 {
285  if (i<_num_accel_instances &&
286  _accel_fd[i] != -1 &&
287  ::read(_accel_fd[i], &accel_report, sizeof(accel_report)) == sizeof(accel_report) &&
288  accel_report.timestamp != _last_accel_timestamp[i]) {
289  return true;
290  }
291  return false;
292 }
293 
294 bool AP_InertialSensor_PX4::_get_gyro_sample(uint8_t i, struct gyro_report &gyro_report)
295 {
296  if (i<_num_gyro_instances &&
297  _gyro_fd[i] != -1 &&
298  ::read(_gyro_fd[i], &gyro_report, sizeof(gyro_report)) == sizeof(gyro_report) &&
299  gyro_report.timestamp != _last_gyro_timestamp[i]) {
300  return true;
301  }
302  return false;
303 }
304 
305 #endif // CONFIG_HAL_BOARD
306 
void _set_gyro_error_count(uint8_t instance, uint32_t error_count)
int printf(const char *fmt,...)
Definition: stdio.c:113
Vector3< float > Vector3f
Definition: vector3.h:246
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint8_t _gyro_instance[INS_MAX_INSTANCES]
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
void _new_gyro_sample(uint8_t i, gyro_report &gyro_report)
uint64_t _last_accel_timestamp[INS_MAX_INSTANCES]
AP_InertialSensor_PX4(AP_InertialSensor &imu)
void _new_accel_sample(uint8_t i, accel_report &accel_report)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
uint64_t _last_gyro_timestamp[INS_MAX_INSTANCES]
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
uint8_t _accel_instance[INS_MAX_INSTANCES]
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
int _accel_fd[INS_MAX_INSTANCES]
#define f(i)
float _accel_sample_time[INS_MAX_INSTANCES]
float _gyro_sample_time[INS_MAX_INSTANCES]
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
void _set_accel_error_count(uint8_t instance, uint32_t error_count)
void _publish_temperature(uint8_t instance, float temperature)
bool _get_gyro_sample(uint8_t i, struct gyro_report &gyro_report)
uint8_t _queue_depth(uint16_t sensor_sample_rate) const
bool _get_accel_sample(uint8_t i, struct accel_report &accel_report)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define INS_MAX_INSTANCES
uint32_t micros()
Definition: system.cpp:152
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
int _gyro_fd[INS_MAX_INSTANCES]