2011-12-21 00:30:22 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-11-12 23:20:25 -04:00
|
|
|
|
|
|
|
#ifndef __AP_INERTIAL_SENSOR_MPU6000_H__
|
|
|
|
#define __AP_INERTIAL_SENSOR_MPU6000_H__
|
|
|
|
|
|
|
|
#include <stdint.h>
|
2012-10-11 21:27:19 -03:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_Math.h>
|
2012-12-12 17:57:34 -04:00
|
|
|
#include <AP_Progmem.h>
|
2011-11-12 23:20:25 -04:00
|
|
|
#include "AP_InertialSensor.h"
|
|
|
|
|
2012-09-28 07:21:59 -03:00
|
|
|
#define MPU6000_CS_PIN 53 // APM pin connected to mpu6000's chip select pin
|
2012-07-28 02:14:43 -03:00
|
|
|
|
2012-12-27 06:28:41 -04:00
|
|
|
// enable debug to see a register dump on startup
|
|
|
|
#define MPU6000_DEBUG 0
|
|
|
|
|
2011-11-12 23:20:25 -04:00
|
|
|
class AP_InertialSensor_MPU6000 : public AP_InertialSensor
|
|
|
|
{
|
2012-08-17 03:19:57 -03:00
|
|
|
public:
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2012-09-28 07:21:59 -03:00
|
|
|
AP_InertialSensor_MPU6000();
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2012-08-17 03:19:57 -03:00
|
|
|
/* Concrete implementation of AP_InertialSensor functions: */
|
|
|
|
bool update();
|
|
|
|
float get_gyro_drift_rate();
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2013-10-08 03:28:39 -03:00
|
|
|
// wait for a sample to be available, with timeout in milliseconds
|
|
|
|
bool wait_for_sample(uint16_t timeout_ms);
|
|
|
|
|
2012-11-05 00:27:03 -04:00
|
|
|
// get_delta_time returns the time period in seconds overwhich the sensor data was collected
|
2013-01-11 06:17:21 -04:00
|
|
|
float get_delta_time();
|
2012-08-30 04:48:36 -03:00
|
|
|
|
2013-10-29 18:54:03 -03:00
|
|
|
uint16_t error_count(void) const { return _error_count; }
|
2013-12-08 05:43:53 -04:00
|
|
|
bool healthy(void) const { return _error_count <= 4; }
|
2014-01-22 07:08:28 -04:00
|
|
|
bool get_gyro_health(uint8_t instance) const { return healthy(); }
|
|
|
|
bool get_accel_health(uint8_t instance) const { return healthy(); }
|
2013-10-29 18:54:03 -03:00
|
|
|
|
2012-11-07 02:20:22 -04:00
|
|
|
protected:
|
2012-10-11 21:27:19 -03:00
|
|
|
uint16_t _init_sensor( Sample_rate sample_rate );
|
2012-11-07 02:20:22 -04:00
|
|
|
|
2012-08-17 03:19:57 -03:00
|
|
|
private:
|
2013-10-29 03:42:35 -03:00
|
|
|
AP_HAL::DigitalSource *_drdy_pin;
|
2011-12-26 16:34:18 -04:00
|
|
|
|
2013-12-08 05:43:53 -04:00
|
|
|
bool _sample_available();
|
2013-09-28 03:29:24 -03:00
|
|
|
void _read_data_transaction();
|
|
|
|
bool _data_ready();
|
|
|
|
void _poll_data(void);
|
|
|
|
uint8_t _register_read( uint8_t reg );
|
2013-10-29 03:42:35 -03:00
|
|
|
void _register_write( uint8_t reg, uint8_t val );
|
|
|
|
bool _hardware_init(Sample_rate sample_rate);
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2013-09-28 03:29:24 -03:00
|
|
|
AP_HAL::SPIDeviceDriver *_spi;
|
|
|
|
AP_HAL::Semaphore *_spi_sem;
|
2012-10-11 21:27:19 -03:00
|
|
|
|
2013-01-11 06:17:21 -04:00
|
|
|
uint16_t _num_samples;
|
2012-08-17 03:19:57 -03:00
|
|
|
static const float _gyro_scale;
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2013-09-28 03:29:24 -03:00
|
|
|
uint32_t _last_sample_time_micros;
|
|
|
|
|
2012-08-17 03:19:57 -03:00
|
|
|
// ensure we can't initialise twice
|
|
|
|
bool _initialised;
|
2013-09-28 03:29:24 -03:00
|
|
|
int16_t _mpu6000_product_id;
|
2012-07-28 02:14:43 -03:00
|
|
|
|
2013-02-06 19:23:08 -04:00
|
|
|
// how many hardware samples before we report a sample to the caller
|
|
|
|
uint8_t _sample_shift;
|
|
|
|
|
|
|
|
// support for updating filter at runtime
|
|
|
|
uint8_t _last_filter_hz;
|
|
|
|
|
|
|
|
void _set_filter_register(uint8_t filter_hz, uint8_t default_filter);
|
|
|
|
|
2013-10-28 04:20:47 -03:00
|
|
|
uint16_t _error_count;
|
2013-10-29 03:42:35 -03:00
|
|
|
|
|
|
|
// accumulation in timer - must be read with timer disabled
|
|
|
|
// the sum of the values since last read
|
|
|
|
Vector3l _accel_sum;
|
|
|
|
Vector3l _gyro_sum;
|
|
|
|
volatile int16_t _sum_count;
|
2013-10-28 04:20:47 -03:00
|
|
|
|
2012-07-28 02:14:43 -03:00
|
|
|
public:
|
2012-12-27 06:28:41 -04:00
|
|
|
|
|
|
|
#if MPU6000_DEBUG
|
|
|
|
void _dump_registers(void);
|
|
|
|
#endif
|
2011-11-12 23:20:25 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_INERTIAL_SENSOR_MPU6000_H__
|