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_H__
# define __AP_INERTIAL_SENSOR_H__
2012-11-05 00:27:03 -04:00
# include "../AP_Math/AP_Math.h"
2011-11-12 23:20:25 -04:00
# include "../AP_PeriodicProcess/AP_PeriodicProcess.h"
2012-11-05 00:27:03 -04:00
# define GRAVITY 9.80665
// Gyro and Accelerometer calibration criteria
# define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0
# define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0
2011-11-12 23:20:25 -04:00
/* AP_InertialSensor is an abstraction for gyro and accel measurements
* which are correctly aligned to the body axes and scaled to SI units .
2012-12-04 20:20:31 -04:00
*
* Gauss - Newton accel calibration routines borrowed from Rolfe Schmidt
* blog post describing the method : http : //chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/
* original sketch available at http : //rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde
2011-11-12 23:20:25 -04:00
*/
class AP_InertialSensor
{
2012-08-17 03:19:56 -03:00
public :
2012-11-05 00:27:03 -04:00
AP_InertialSensor ( ) ;
enum Start_style {
COLD_START = 0 ,
WARM_START
} ;
2012-11-29 07:56:13 -04:00
// the rate that updates will be available to the application
enum Sample_rate {
RATE_50HZ ,
RATE_100HZ ,
RATE_200HZ
} ;
2012-11-05 00:27:03 -04:00
/// Perform startup initialisation.
///
/// Called to initialise the state of the IMU.
///
/// For COLD_START, implementations using real sensors can assume
/// that the airframe is stationary and nominally oriented.
///
/// For WARM_START, no assumptions should be made about the
/// orientation or motion of the airframe. Calibration should be
/// as for the previous COLD_START call.
///
/// @param style The initialisation startup style.
///
virtual void init ( Start_style style ,
2012-11-29 07:56:13 -04:00
Sample_rate sample_rate ,
2012-11-05 00:27:03 -04:00
void ( * delay_cb ) ( unsigned long t ) ,
void ( * flash_leds_cb ) ( bool on ) ,
AP_PeriodicProcess * scheduler ) ;
/// Perform cold startup initialisation for just the accelerometers.
///
/// @note This should not be called unless ::init has previously
/// been called, as ::init may perform other work.
///
2012-11-07 02:20:22 -04:00
virtual void init_accel ( void ( * delay_cb ) ( unsigned long t ) , void ( * flash_leds_cb ) ( bool on ) ) ;
2012-11-05 00:27:03 -04:00
2012-11-20 03:41:04 -04:00
# if !defined( __AVR_ATmega1280__ )
2012-11-05 00:27:03 -04:00
// perform accelerometer calibration including providing user instructions and feedback
2012-11-20 03:26:51 -04:00
virtual bool calibrate_accel ( void ( * delay_cb ) ( unsigned long t ) ,
2012-11-21 01:18:21 -04:00
void ( * flash_leds_cb ) ( bool on ) ,
void ( * send_msg ) ( const prog_char_t * , . . . ) ,
void ( * wait_key ) ( void ) ) ;
2012-11-20 03:41:04 -04:00
# endif
2012-11-05 00:27:03 -04:00
/// Perform cold-start initialisation for just the gyros.
///
/// @note This should not be called unless ::init has previously
/// been called, as ::init may perform other work
///
virtual void init_gyro ( void ( * callback ) ( unsigned long t ) , void ( * flash_leds_cb ) ( bool on ) ) ;
/// Fetch the current gyro values
///
/// @returns vector of rotational rates in radians/sec
///
Vector3f get_gyro ( void ) { return _gyro ; }
2012-12-03 08:27:21 -04:00
void set_gyro ( Vector3f gyro ) { _gyro = gyro ; }
2012-11-05 00:27:03 -04:00
// set gyro offsets in radians/sec
Vector3f get_gyro_offsets ( void ) { return _gyro_offset ; }
void set_gyro_offsets ( Vector3f offsets ) { _gyro_offset . set ( offsets ) ; }
/// Fetch the current accelerometer values
///
/// @returns vector of current accelerations in m/s/s
///
Vector3f get_accel ( void ) { return _accel ; }
2012-12-03 08:27:21 -04:00
void set_accel ( Vector3f accel ) { _accel = accel ; }
2012-11-05 00:27:03 -04:00
// get accel offsets in m/s/s
Vector3f get_accel_offsets ( ) { return _accel_offset ; }
void set_accel_offsets ( Vector3f offsets ) { _accel_offset . set ( offsets ) ; }
// get accel scale
Vector3f get_accel_scale ( ) { return _accel_scale ; }
2012-08-17 03:19:56 -03:00
/* Update the sensor data, so that getters are nonblocking.
* Returns a bool of whether data was updated or not .
*/
2012-11-05 00:27:03 -04:00
virtual bool update ( ) = 0 ;
2012-08-17 03:19:56 -03:00
// check if the sensors have new data
2012-11-05 00:27:03 -04:00
virtual bool new_data_available ( void ) = 0 ;
2012-08-17 03:19:56 -03:00
/* Temperature, in degrees celsius, of the gyro. */
virtual float temperature ( ) = 0 ;
2012-11-05 00:27:03 -04:00
/* get_delta_time returns the time period in seconds
2012-08-30 04:48:36 -03:00
* overwhich the sensor data was collected
2012-08-17 03:19:56 -03:00
*/
2012-11-05 00:27:03 -04:00
virtual float get_delta_time ( ) { return ( float ) get_delta_time_micros ( ) * 1.0e-6 ; }
virtual uint32_t get_delta_time_micros ( ) = 0 ;
// get_last_sample_time_micros returns the time in microseconds that the last sample was taken
//virtual uint32_t get_last_sample_time_micros() = 0;
2012-08-17 03:19:56 -03:00
// return the maximum gyro drift rate in radians/s/s. This
// depends on what gyro chips are being used
2012-11-05 00:27:03 -04:00
virtual float get_gyro_drift_rate ( void ) = 0 ;
2012-03-08 03:10:27 -04:00
2012-08-30 04:48:36 -03:00
// get number of samples read from the sensors
2012-11-05 00:27:03 -04:00
virtual uint16_t num_samples_available ( ) = 0 ;
// class level parameters
static const struct AP_Param : : GroupInfo var_info [ ] ;
protected :
2012-11-07 02:20:22 -04:00
// sensor specific init to be overwritten by descendant classes
2012-11-29 07:56:13 -04:00
virtual uint16_t _init_sensor ( AP_PeriodicProcess * scheduler , Sample_rate sample_rate ) = 0 ;
2012-11-07 02:20:22 -04:00
2012-11-05 00:27:03 -04:00
// no-save implementations of accel and gyro initialisation routines
virtual void _init_accel ( void ( * delay_cb ) ( unsigned long t ) ,
void ( * flash_leds_cb ) ( bool on ) = NULL ) ;
virtual void _init_gyro ( void ( * delay_cb ) ( unsigned long t ) ,
void ( * flash_leds_cb ) ( bool on ) = NULL ) ;
2012-11-20 03:41:04 -04:00
# if !defined( __AVR_ATmega1280__ )
2012-12-04 20:20:31 -04:00
// Calibration routines borrowed from Rolfe Schmidt
// blog post describing the method: http://chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/
// original sketch available at http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde
2012-11-05 00:27:03 -04:00
// _calibrate_accel - perform low level accel calibration
2012-11-07 02:20:22 -04:00
virtual bool _calibrate_accel ( Vector3f accel_sample [ 6 ] , Vector3f & accel_offsets , Vector3f & accel_scale ) ;
2012-11-05 00:27:03 -04:00
virtual void _calibrate_update_matrices ( float dS [ 6 ] , float JS [ 6 ] [ 6 ] , float beta [ 6 ] , float data [ 3 ] ) ;
virtual void _calibrate_reset_matrices ( float dS [ 6 ] , float JS [ 6 ] [ 6 ] ) ;
virtual void _calibrate_find_delta ( float dS [ 6 ] , float JS [ 6 ] [ 6 ] , float delta [ 6 ] ) ;
2012-11-20 03:41:04 -04:00
# endif
2012-11-05 00:27:03 -04:00
// save parameters to eeprom
2012-11-07 02:20:22 -04:00
void _save_parameters ( ) ;
2012-11-05 00:27:03 -04:00
// Most recent accelerometer reading obtained by ::update
Vector3f _accel ;
// Most recent gyro reading obtained by ::update
Vector3f _gyro ;
// product id
AP_Int16 _product_id ;
2012-08-30 04:48:36 -03:00
2012-11-05 00:27:03 -04:00
// accelerometer scaling and offsets
AP_Vector3f _accel_scale ;
AP_Vector3f _accel_offset ;
AP_Vector3f _gyro_offset ;
2012-11-29 16:15:12 -04:00
// filtering frequency (0 means default)
AP_Int8 _mpu6000_filter ;
2011-11-12 23:20:25 -04:00
} ;
# include "AP_InertialSensor_Oilpan.h"
# include "AP_InertialSensor_MPU6000.h"
2011-11-13 02:42:20 -04:00
# include "AP_InertialSensor_Stub.h"
2011-11-12 23:20:25 -04:00
# endif // __AP_INERTIAL_SENSOR_H__