4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 8 #include <drivers/drv_accel.h> 9 #include <drivers/drv_gyro.h> 10 #include <uORB/uORB.h> 11 #include <uORB/topics/sensor_combined.h> 60 #ifdef AP_INERTIALSENSOR_PX4_DEBUG 69 #endif // AP_INERTIALSENSOR_PX4_DEBUG 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)
uint8_t _num_gyro_instances
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)
uint8_t _num_accel_instances
void accumulate(void) override
#define INS_MAX_INSTANCES
int _gyro_fd[INS_MAX_INSTANCES]