2013-01-03 23:25:57 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#ifndef __AP_INERTIAL_SENSOR_PX4_H__
|
|
|
|
#define __AP_INERTIAL_SENSOR_PX4_H__
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-12-30 07:01:24 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
2013-01-03 23:25:57 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Progmem/AP_Progmem.h>
|
2013-01-03 23:25:57 -04:00
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
#include <drivers/drv_accel.h>
|
|
|
|
#include <drivers/drv_gyro.h>
|
|
|
|
#include <uORB/uORB.h>
|
|
|
|
#include <uORB/topics/sensor_combined.h>
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <Filter/Filter.h>
|
|
|
|
#include <Filter/LowPassFilter2p.h>
|
2015-02-17 05:58:09 -04:00
|
|
|
|
2014-10-15 05:54:30 -03:00
|
|
|
class AP_InertialSensor_PX4 : public AP_InertialSensor_Backend
|
2013-01-03 23:25:57 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
2014-10-15 05:54:30 -03:00
|
|
|
AP_InertialSensor_PX4(AP_InertialSensor &imu);
|
2013-01-03 23:25:57 -04:00
|
|
|
|
2014-10-15 05:54:30 -03:00
|
|
|
/* update accel and gyro state */
|
|
|
|
bool update();
|
2013-12-08 05:44:31 -04:00
|
|
|
|
2014-10-15 05:54:30 -03:00
|
|
|
// detect the sensor
|
2014-10-16 17:52:21 -03:00
|
|
|
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);
|
2013-12-08 05:44:31 -04:00
|
|
|
|
2014-10-15 05:54:30 -03:00
|
|
|
bool gyro_sample_available(void);
|
|
|
|
bool accel_sample_available(void);
|
2014-02-27 01:27:46 -04:00
|
|
|
|
2013-01-03 23:25:57 -04:00
|
|
|
private:
|
2014-10-16 17:52:21 -03:00
|
|
|
bool _init_sensor(void);
|
2013-08-06 03:31:18 -03:00
|
|
|
void _get_sample(void);
|
2013-12-08 05:44:31 -04:00
|
|
|
bool _sample_available(void);
|
2013-12-08 18:50:12 -04:00
|
|
|
Vector3f _accel_in[INS_MAX_INSTANCES];
|
|
|
|
Vector3f _gyro_in[INS_MAX_INSTANCES];
|
|
|
|
uint64_t _last_accel_timestamp[INS_MAX_INSTANCES];
|
|
|
|
uint64_t _last_gyro_timestamp[INS_MAX_INSTANCES];
|
2014-10-15 05:54:30 -03:00
|
|
|
uint64_t _last_accel_update_timestamp[INS_MAX_INSTANCES];
|
|
|
|
uint64_t _last_gyro_update_timestamp[INS_MAX_INSTANCES];
|
2015-06-16 22:55:37 -03:00
|
|
|
float _accel_sample_time[INS_MAX_INSTANCES];
|
|
|
|
float _gyro_sample_time[INS_MAX_INSTANCES];
|
2013-12-14 00:33:46 -04:00
|
|
|
uint64_t _last_get_sample_timestamp;
|
2013-08-06 03:31:18 -03:00
|
|
|
uint64_t _last_sample_timestamp;
|
2013-01-20 06:13:52 -04:00
|
|
|
|
2015-02-17 05:58:09 -04:00
|
|
|
void _new_accel_sample(uint8_t i, accel_report &accel_report);
|
|
|
|
void _new_gyro_sample(uint8_t i, gyro_report &gyro_report);
|
|
|
|
|
2015-02-19 03:33:35 -04:00
|
|
|
bool _get_gyro_sample(uint8_t i, struct gyro_report &gyro_report);
|
|
|
|
bool _get_accel_sample(uint8_t i, struct accel_report &accel_report);
|
|
|
|
|
2015-03-11 20:02:36 -03:00
|
|
|
// calculate right queue depth for a sensor
|
|
|
|
uint8_t _queue_depth(uint16_t sensor_sample_rate) const;
|
|
|
|
|
2015-03-11 21:58:36 -03:00
|
|
|
// support for updating filter at runtime (-1 means unset)
|
|
|
|
int8_t _last_gyro_filter_hz;
|
|
|
|
int8_t _last_accel_filter_hz;
|
2013-02-06 20:20:45 -04:00
|
|
|
|
2015-03-11 21:58:36 -03:00
|
|
|
void _set_gyro_filter_frequency(uint8_t filter_hz);
|
|
|
|
void _set_accel_filter_frequency(uint8_t filter_hz);
|
2013-02-06 20:20:45 -04:00
|
|
|
|
2013-01-20 06:13:52 -04:00
|
|
|
// accelerometer and gyro driver handles
|
2013-12-08 05:44:31 -04:00
|
|
|
uint8_t _num_accel_instances;
|
|
|
|
uint8_t _num_gyro_instances;
|
2014-10-15 05:54:30 -03:00
|
|
|
|
2013-12-08 18:50:12 -04:00
|
|
|
int _accel_fd[INS_MAX_INSTANCES];
|
|
|
|
int _gyro_fd[INS_MAX_INSTANCES];
|
2014-10-15 05:54:30 -03:00
|
|
|
|
|
|
|
// indexes in frontend object. Note that these could be different
|
|
|
|
// from the backend indexes
|
|
|
|
uint8_t _accel_instance[INS_MAX_INSTANCES];
|
|
|
|
uint8_t _gyro_instance[INS_MAX_INSTANCES];
|
2015-02-17 05:58:09 -04:00
|
|
|
|
|
|
|
// Low Pass filters for gyro and accel
|
|
|
|
LowPassFilter2pVector3f _accel_filter[INS_MAX_INSTANCES];
|
|
|
|
LowPassFilter2pVector3f _gyro_filter[INS_MAX_INSTANCES];
|
|
|
|
|
2015-02-20 04:34:14 -04:00
|
|
|
#ifdef AP_INERTIALSENSOR_PX4_DEBUG
|
|
|
|
uint32_t _gyro_meas_count[INS_MAX_INSTANCES];
|
|
|
|
uint32_t _accel_meas_count[INS_MAX_INSTANCES];
|
|
|
|
|
|
|
|
uint32_t _gyro_meas_count_start_us[INS_MAX_INSTANCES];
|
|
|
|
uint32_t _accel_meas_count_start_us[INS_MAX_INSTANCES];
|
|
|
|
|
|
|
|
float _gyro_dt_max[INS_MAX_INSTANCES];
|
|
|
|
float _accel_dt_max[INS_MAX_INSTANCES];
|
|
|
|
#endif // AP_INERTIALSENSOR_PX4_DEBUG
|
2013-01-03 23:25:57 -04:00
|
|
|
};
|
2014-10-22 17:29:03 -03:00
|
|
|
#endif // CONFIG_HAL_BOARD
|
2013-01-03 23:25:57 -04:00
|
|
|
#endif // __AP_INERTIAL_SENSOR_PX4_H__
|