2014-05-01 17:41:22 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#ifndef __AP_INERTIAL_SENSOR_MPU9250_H__
|
|
|
|
#define __AP_INERTIAL_SENSOR_MPU9250_H__
|
|
|
|
|
|
|
|
#include <stdint.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <Filter/Filter.h>
|
|
|
|
#include <Filter/LowPassFilter2p.h>
|
2014-05-01 17:41:22 -03:00
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
|
|
|
|
// enable debug to see a register dump on startup
|
|
|
|
#define MPU9250_DEBUG 0
|
|
|
|
|
2014-10-15 20:31:06 -03:00
|
|
|
class AP_InertialSensor_MPU9250 : public AP_InertialSensor_Backend
|
2014-05-01 17:41:22 -03:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
2014-10-15 20:31:06 -03:00
|
|
|
AP_InertialSensor_MPU9250(AP_InertialSensor &imu);
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2014-10-15 20:31:06 -03:00
|
|
|
/* update accel and gyro state */
|
|
|
|
bool update();
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2014-10-15 20:31:06 -03:00
|
|
|
bool gyro_sample_available(void) { return _have_sample_available; }
|
|
|
|
bool accel_sample_available(void) { return _have_sample_available; }
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2015-07-02 20:27:55 -03:00
|
|
|
/* Put the MPU9250 in a known state so it can be
|
|
|
|
* used both for the InertialSensor and as for backend of other drivers.
|
|
|
|
*
|
|
|
|
* The SPI semaphore must be taken and timer_procs suspended.
|
|
|
|
*
|
|
|
|
* This method puts the bus in low speed. If the initialization is
|
|
|
|
* successful the bus is left on low speed so the caller can finish the
|
|
|
|
* initialization of its driver.
|
|
|
|
*/
|
2015-09-18 16:11:16 -03:00
|
|
|
static bool initialize_driver_state(AP_HAL::SPIDeviceDriver *spi);
|
2015-07-02 20:27:55 -03:00
|
|
|
|
2014-10-15 20:31:06 -03:00
|
|
|
// detect the sensor
|
2015-09-18 16:11:16 -03:00
|
|
|
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu, AP_HAL::SPIDeviceDriver *spi);
|
2014-05-01 17:41:22 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
2015-07-02 17:33:22 -03:00
|
|
|
static uint8_t _register_read(AP_HAL::SPIDeviceDriver *spi, uint8_t reg);
|
|
|
|
static void _register_write(AP_HAL::SPIDeviceDriver *spi, uint8_t reg,
|
|
|
|
uint8_t val);
|
|
|
|
|
2015-09-18 16:11:16 -03:00
|
|
|
bool _init_sensor(AP_HAL::SPIDeviceDriver *spi);
|
2014-05-01 17:41:22 -03:00
|
|
|
void _read_data_transaction();
|
|
|
|
bool _data_ready();
|
|
|
|
void _poll_data(void);
|
|
|
|
uint8_t _register_read( uint8_t reg );
|
|
|
|
void _register_write( uint8_t reg, uint8_t val );
|
2014-10-16 17:52:21 -03:00
|
|
|
bool _hardware_init(void);
|
2014-08-19 06:39:21 -03:00
|
|
|
bool _sample_available();
|
2014-05-01 17:41:22 -03:00
|
|
|
|
|
|
|
AP_HAL::SPIDeviceDriver *_spi;
|
|
|
|
AP_HAL::Semaphore *_spi_sem;
|
|
|
|
|
|
|
|
// support for updating filter at runtime
|
2015-03-11 21:58:36 -03:00
|
|
|
int16_t _last_gyro_filter_hz;
|
|
|
|
int16_t _last_accel_filter_hz;
|
2014-08-19 06:39:21 -03:00
|
|
|
|
|
|
|
// change the filter frequency
|
2015-03-11 21:58:36 -03:00
|
|
|
void _set_accel_filter(uint8_t filter_hz);
|
|
|
|
void _set_gyro_filter(uint8_t filter_hz);
|
2014-08-19 06:39:21 -03:00
|
|
|
|
2014-08-20 18:48:44 -03:00
|
|
|
// This structure is used to pass data from the timer which reads
|
|
|
|
// the sensor to the main thread. The _shared_data_idx is used to
|
|
|
|
// prevent race conditions by ensuring the data is fully updated
|
|
|
|
// before being used by the consumer
|
|
|
|
struct {
|
|
|
|
Vector3f _accel_filtered;
|
|
|
|
Vector3f _gyro_filtered;
|
|
|
|
} _shared_data[2];
|
|
|
|
volatile uint8_t _shared_data_idx;
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2014-08-19 06:39:21 -03:00
|
|
|
// Low Pass filters for gyro and accel
|
2015-02-17 18:48:26 -04:00
|
|
|
LowPassFilter2pVector3f _accel_filter;
|
|
|
|
LowPassFilter2pVector3f _gyro_filter;
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2014-08-19 06:39:21 -03:00
|
|
|
// do we currently have a sample pending?
|
|
|
|
bool _have_sample_available;
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2014-10-15 20:31:06 -03:00
|
|
|
// gyro and accel instances
|
|
|
|
uint8_t _gyro_instance;
|
|
|
|
uint8_t _accel_instance;
|
2014-05-01 17:41:22 -03:00
|
|
|
|
2015-06-08 17:06:17 -03:00
|
|
|
// The default rotation for the IMU, its value depends on how the IMU is
|
|
|
|
// placed by default on the system
|
|
|
|
enum Rotation _default_rotation;
|
|
|
|
|
2014-05-01 17:41:22 -03:00
|
|
|
#if MPU9250_DEBUG
|
2015-07-02 17:33:22 -03:00
|
|
|
static void _dump_registers(AP_HAL::SPIDeviceDriver *spi);
|
2014-05-01 17:41:22 -03:00
|
|
|
#endif
|
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_INERTIAL_SENSOR_MPU9250_H__
|