mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor_MPU9150: I2C userspace driver sensor added.
The MPU9150 is a 9 axis sensor that includes 3 accelerometers, 3 gyroscopes and 3 magnetometers. All accessible through I2C. The AP_InertialSensor_MPU9150 class allows APM to use this sensor.
This commit is contained in:
parent
1445781104
commit
44320708a7
|
@ -227,5 +227,6 @@ protected:
|
|||
#include "AP_InertialSensor_UserInteract_MAVLink.h"
|
||||
#include "AP_InertialSensor_Flymaple.h"
|
||||
#include "AP_InertialSensor_L3G4200D.h"
|
||||
#include "AP_InertialSensor_MPU9150.h"
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_H__
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,69 @@
|
|||
/// -*- 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>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include <AP_Progmem.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
#include <Filter.h>
|
||||
#include <LowPassFilter2p.h>
|
||||
|
||||
|
||||
class AP_InertialSensor_MPU9150 : public AP_InertialSensor
|
||||
{
|
||||
public:
|
||||
|
||||
AP_InertialSensor_MPU9150();
|
||||
|
||||
/* Implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
||||
float get_delta_time() const;
|
||||
float get_gyro_drift_rate();
|
||||
bool wait_for_sample(uint16_t timeout_ms);
|
||||
|
||||
private:
|
||||
uint16_t _init_sensor( Sample_rate sample_rate );
|
||||
void _accumulate(void);
|
||||
bool _sample_available();
|
||||
// uint64_t _last_update_usec;
|
||||
Vector3f _accel_filtered;
|
||||
Vector3f _gyro_filtered;
|
||||
uint32_t _sample_period_usec;
|
||||
uint32_t _last_sample_time;
|
||||
volatile uint32_t _gyro_samples_available;
|
||||
volatile uint8_t _gyro_samples_needed;
|
||||
|
||||
// // support for updating filter at runtime
|
||||
uint8_t _last_filter_hz;
|
||||
uint8_t _default_filter_hz;
|
||||
|
||||
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);
|
||||
|
||||
// Filter (specify which one)
|
||||
void _set_filter_frequency(uint8_t filter_hz);
|
||||
|
||||
// Low Pass filters for gyro and accel
|
||||
LowPassFilter2p _accel_filter_x;
|
||||
LowPassFilter2p _accel_filter_y;
|
||||
LowPassFilter2p _accel_filter_z;
|
||||
LowPassFilter2p _gyro_filter_x;
|
||||
LowPassFilter2p _gyro_filter_y;
|
||||
LowPassFilter2p _gyro_filter_z;
|
||||
|
||||
|
||||
};
|
||||
#endif
|
||||
#endif // __AP_INERTIAL_SENSOR_MPU9150_H__
|
|
@ -0,0 +1,202 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
//
|
||||
// Simple test for the AP_InertialSensor driver.
|
||||
//
|
||||
|
||||
#include <stdarg.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_FLYMAPLE.h>
|
||||
#include <AP_HAL_AVR_SITL.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_Linux.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_Notify.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_NavEKF.h>
|
||||
#include <AP_HAL_Linux.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_Vehicle.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_ADC_AnalogSource.h>
|
||||
#include <DataFlash.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
AP_InertialSensor_MPU9150 ins;
|
||||
|
||||
void setup(void)
|
||||
{
|
||||
hal.console->println("AP_InertialSensor startup...");
|
||||
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
AP_InertialSensor::RATE_400HZ);
|
||||
|
||||
// display initial values
|
||||
display_offsets_and_scaling();
|
||||
hal.console->println("Complete. Reading:");
|
||||
}
|
||||
|
||||
void loop(void)
|
||||
{
|
||||
int16_t user_input;
|
||||
|
||||
hal.console->println();
|
||||
hal.console->println_P(PSTR(
|
||||
"Menu:\r\n"
|
||||
" c) calibrate accelerometers\r\n"
|
||||
" d) display offsets and scaling\r\n"
|
||||
" l) level (capture offsets from level)\r\n"
|
||||
" t) test\r\n"
|
||||
" r) reboot"));
|
||||
|
||||
// wait for user input
|
||||
while( !hal.console->available() ) {
|
||||
hal.scheduler->delay(20);
|
||||
}
|
||||
|
||||
// read in user input
|
||||
while( hal.console->available() ) {
|
||||
user_input = hal.console->read();
|
||||
|
||||
if( user_input == 'c' || user_input == 'C' ) {
|
||||
run_calibration();
|
||||
display_offsets_and_scaling();
|
||||
}
|
||||
|
||||
if( user_input == 'd' || user_input == 'D' ) {
|
||||
display_offsets_and_scaling();
|
||||
}
|
||||
|
||||
if( user_input == 'l' || user_input == 'L' ) {
|
||||
run_level();
|
||||
display_offsets_and_scaling();
|
||||
}
|
||||
|
||||
if( user_input == 't' || user_input == 'T' ) {
|
||||
run_test();
|
||||
}
|
||||
|
||||
if( user_input == 'r' || user_input == 'R' ) {
|
||||
hal.scheduler->reboot(false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void run_calibration()
|
||||
{
|
||||
float roll_trim, pitch_trim;
|
||||
// clear off any other characters (like line feeds,etc)
|
||||
while( hal.console->available() ) {
|
||||
hal.console->read();
|
||||
}
|
||||
|
||||
|
||||
#if !defined( __AVR_ATmega1280__ )
|
||||
AP_InertialSensor_UserInteractStream interact(hal.console);
|
||||
ins.calibrate_accel(&interact, roll_trim, pitch_trim);
|
||||
#else
|
||||
hal.console->println_P(PSTR("calibrate_accel not available on 1280"));
|
||||
#endif
|
||||
}
|
||||
|
||||
void display_offsets_and_scaling()
|
||||
{
|
||||
Vector3f accel_offsets = ins.get_accel_offsets();
|
||||
Vector3f accel_scale = ins.get_accel_scale();
|
||||
Vector3f gyro_offsets = ins.get_gyro_offsets();
|
||||
|
||||
// display results
|
||||
hal.console->printf_P(
|
||||
PSTR("\nAccel Offsets X:%10.8f \t Y:%10.8f \t Z:%10.8f\n"),
|
||||
accel_offsets.x,
|
||||
accel_offsets.y,
|
||||
accel_offsets.z);
|
||||
hal.console->printf_P(
|
||||
PSTR("Accel Scale X:%10.8f \t Y:%10.8f \t Z:%10.8f\n"),
|
||||
accel_scale.x,
|
||||
accel_scale.y,
|
||||
accel_scale.z);
|
||||
hal.console->printf_P(
|
||||
PSTR("Gyro Offsets X:%10.8f \t Y:%10.8f \t Z:%10.8f\n"),
|
||||
gyro_offsets.x,
|
||||
gyro_offsets.y,
|
||||
gyro_offsets.z);
|
||||
}
|
||||
|
||||
void run_level()
|
||||
{
|
||||
// clear off any input in the buffer
|
||||
while( hal.console->available() ) {
|
||||
hal.console->read();
|
||||
}
|
||||
|
||||
// display message to user
|
||||
hal.console->print("Place APM on a level surface and press any key..\n");
|
||||
|
||||
// wait for user input
|
||||
while( !hal.console->available() ) {
|
||||
hal.scheduler->delay(20);
|
||||
}
|
||||
while( hal.console->available() ) {
|
||||
hal.console->read();
|
||||
}
|
||||
|
||||
// run accel level
|
||||
ins.init_accel();
|
||||
|
||||
// display results
|
||||
display_offsets_and_scaling();
|
||||
}
|
||||
|
||||
void run_test()
|
||||
{
|
||||
Vector3f accel;
|
||||
Vector3f gyro;
|
||||
float length;
|
||||
uint32_t counter = 0;
|
||||
|
||||
// flush any user input
|
||||
while( hal.console->available() ) {
|
||||
hal.console->read();
|
||||
}
|
||||
|
||||
// clear out any existing samples from ins
|
||||
ins.update();
|
||||
|
||||
// loop as long as user does not press a key
|
||||
while( !hal.console->available() ) {
|
||||
|
||||
// wait until we have a sample
|
||||
ins.wait_for_sample(1000);
|
||||
|
||||
// read samples from ins
|
||||
ins.update();
|
||||
accel = ins.get_accel();
|
||||
gyro = ins.get_gyro();
|
||||
|
||||
length = accel.length();
|
||||
|
||||
if (counter++ % 50 == 0) {
|
||||
// display results
|
||||
hal.console->printf_P(PSTR("Accel X:%4.2f \t Y:%4.2f \t Z:%4.2f \t len:%4.2f \t Gyro X:%4.2f \t Y:%4.2f \t Z:%4.2f\n"),
|
||||
accel.x, accel.y, accel.z, length, gyro.x, gyro.y, gyro.z);
|
||||
}
|
||||
}
|
||||
|
||||
// clear user input
|
||||
while( hal.console->available() ) {
|
||||
hal.console->read();
|
||||
}
|
||||
}
|
||||
|
||||
AP_HAL_MAIN();
|
|
@ -0,0 +1 @@
|
|||
include ../../../../mk/apm.mk
|
Loading…
Reference in New Issue