2014-03-28 09:49:39 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#ifndef __AP_INERTIAL_SENSOR_MPU9150_H__
|
|
|
|
#define __AP_INERTIAL_SENSOR_MPU9150_H__
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
2014-07-06 23:03:57 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2014-03-28 09:49:39 -03:00
|
|
|
|
|
|
|
#include <AP_Progmem.h>
|
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
#include <Filter.h>
|
|
|
|
#include <LowPassFilter2p.h>
|
|
|
|
|
|
|
|
|
2014-10-15 22:03:28 -03:00
|
|
|
class AP_InertialSensor_MPU9150 : public AP_InertialSensor_Backend
|
2014-03-28 09:49:39 -03:00
|
|
|
{
|
|
|
|
public:
|
2014-10-15 22:03:28 -03:00
|
|
|
AP_InertialSensor_MPU9150(AP_InertialSensor &imu);
|
2014-03-28 09:49:39 -03:00
|
|
|
|
2014-10-15 22:03:28 -03:00
|
|
|
/* update accel and gyro state */
|
|
|
|
bool update();
|
2014-03-28 09:49:39 -03:00
|
|
|
|
2014-10-15 22:03:28 -03:00
|
|
|
bool gyro_sample_available(void) { return _have_sample_available; }
|
|
|
|
bool accel_sample_available(void) { return _have_sample_available; }
|
|
|
|
|
|
|
|
// detect the sensor
|
2014-10-16 17:52:21 -03:00
|
|
|
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);
|
2014-03-28 09:49:39 -03:00
|
|
|
|
|
|
|
private:
|
2014-10-16 17:52:21 -03:00
|
|
|
bool _init_sensor();
|
2014-03-28 09:49:39 -03:00
|
|
|
void _accumulate(void);
|
|
|
|
Vector3f _accel_filtered;
|
|
|
|
Vector3f _gyro_filtered;
|
2014-10-15 22:03:28 -03:00
|
|
|
bool _have_sample_available;
|
2014-03-28 09:49:39 -03:00
|
|
|
|
|
|
|
// // support for updating filter at runtime
|
2015-03-11 21:58:36 -03:00
|
|
|
uint8_t _last_accel_filter_hz;
|
|
|
|
uint8_t _last_gyro_filter_hz;
|
2014-03-28 09:49:39 -03:00
|
|
|
|
|
|
|
int16_t mpu_set_gyro_fsr(uint16_t fsr);
|
|
|
|
int16_t mpu_set_accel_fsr(uint8_t fsr);
|
|
|
|
int16_t mpu_set_lpf(uint16_t lpf);
|
|
|
|
int16_t mpu_set_sample_rate(uint16_t rate);
|
|
|
|
int16_t mpu_set_compass_sample_rate(uint16_t rate, uint16_t chip_sample_rate);
|
|
|
|
int16_t mpu_configure_fifo(uint8_t sensors);
|
|
|
|
int16_t set_int_enable(uint8_t enable);
|
|
|
|
int16_t mpu_reset_fifo(uint8_t sensors);
|
|
|
|
int16_t mpu_set_sensors(uint8_t sensors);
|
|
|
|
int16_t mpu_set_int_latched(uint8_t enable);
|
|
|
|
int16_t mpu_read_fifo(int16_t *gyro, int16_t *accel, uint32_t timestamp, uint8_t *sensors, uint8_t *more);
|
|
|
|
|
2015-03-11 21:58:36 -03:00
|
|
|
void _set_accel_filter_frequency(uint8_t filter_hz);
|
|
|
|
void _set_gyro_filter_frequency(uint8_t filter_hz);
|
2014-03-28 09:49:39 -03:00
|
|
|
|
|
|
|
// Low Pass filters for gyro and accel
|
2015-02-17 18:48:26 -04:00
|
|
|
LowPassFilter2pVector3f _accel_filter;
|
|
|
|
LowPassFilter2pVector3f _gyro_filter;
|
2014-03-28 09:49:39 -03:00
|
|
|
|
2014-10-15 22:03:28 -03:00
|
|
|
uint8_t _gyro_instance;
|
|
|
|
uint8_t _accel_instance;
|
2014-03-28 09:49:39 -03:00
|
|
|
};
|
|
|
|
#endif
|
|
|
|
#endif // __AP_INERTIAL_SENSOR_MPU9150_H__
|