APM:Libraries
AP_InertialSensor_PX4.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
5 
6 #include "AP_InertialSensor.h"
8 #include <drivers/drv_accel.h>
9 #include <drivers/drv_gyro.h>
10 #include <uORB/uORB.h>
11 #include <uORB/topics/sensor_combined.h>
12 
13 #include <Filter/Filter.h>
14 #include <Filter/LowPassFilter2p.h>
15 
17 {
18 public:
19 
21 
22  /* update accel and gyro state */
23  bool update();
24 
25  // detect the sensor
27 
28  // accumulate more samples
29  void accumulate(void) override { _get_sample(); }
30 
31 private:
32  bool _init_sensor(void);
33  void _get_sample(void);
38 
39  void _new_accel_sample(uint8_t i, accel_report &accel_report);
40  void _new_gyro_sample(uint8_t i, gyro_report &gyro_report);
41 
42  bool _get_gyro_sample(uint8_t i, struct gyro_report &gyro_report);
43  bool _get_accel_sample(uint8_t i, struct accel_report &accel_report);
44 
45  // calculate right queue depth for a sensor
46  uint8_t _queue_depth(uint16_t sensor_sample_rate) const;
47 
48  // accelerometer and gyro driver handles
51 
54 
55  // indexes in frontend object. Note that these could be different
56  // from the backend indexes
59 
60 #ifdef AP_INERTIALSENSOR_PX4_DEBUG
61  uint32_t _gyro_meas_count[INS_MAX_INSTANCES];
62  uint32_t _accel_meas_count[INS_MAX_INSTANCES];
63 
64  uint32_t _gyro_meas_count_start_us[INS_MAX_INSTANCES];
65  uint32_t _accel_meas_count_start_us[INS_MAX_INSTANCES];
66 
67  float _gyro_dt_max[INS_MAX_INSTANCES];
68  float _accel_dt_max[INS_MAX_INSTANCES];
69 #endif // AP_INERTIALSENSOR_PX4_DEBUG
70 };
71 #endif
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
uint8_t _gyro_instance[INS_MAX_INSTANCES]
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)
uint64_t _last_gyro_timestamp[INS_MAX_INSTANCES]
uint8_t _accel_instance[INS_MAX_INSTANCES]
int _accel_fd[INS_MAX_INSTANCES]
float _accel_sample_time[INS_MAX_INSTANCES]
float _gyro_sample_time[INS_MAX_INSTANCES]
A class to implement a second order low pass filter.
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 accumulate(void) override
#define INS_MAX_INSTANCES
int _gyro_fd[INS_MAX_INSTANCES]