2013-05-29 20:54:53 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
//
|
2012-03-11 05:00:39 -03:00
|
|
|
// Simple test for the AP_AHRS interface
|
2012-03-03 00:49:38 -04:00
|
|
|
//
|
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_Progmem.h>
|
|
|
|
#include <AP_Math.h>
|
|
|
|
#include <AP_Param.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
#include <AP_InertialSensor.h>
|
|
|
|
#include <AP_ADC.h>
|
2013-07-15 01:10:17 -03:00
|
|
|
#include <AP_ADC_AnalogSource.h>
|
2014-02-14 03:34:22 -04:00
|
|
|
#include <AP_Baro.h> // ArduPilot Mega Barometer Library
|
2012-03-03 00:49:38 -04:00
|
|
|
#include <AP_GPS.h>
|
2012-03-11 05:00:39 -03:00
|
|
|
#include <AP_AHRS.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
#include <AP_Compass.h>
|
2012-11-14 12:10:15 -04:00
|
|
|
#include <AP_Declination.h>
|
2012-09-13 04:44:39 -03:00
|
|
|
#include <AP_Airspeed.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
#include <AP_Baro.h>
|
|
|
|
#include <GCS_MAVLink.h>
|
2014-03-18 19:35:08 -03:00
|
|
|
#include <AP_Mission.h>
|
2012-03-22 07:13:26 -03:00
|
|
|
#include <Filter.h>
|
2012-12-18 06:27:50 -04:00
|
|
|
#include <SITL.h>
|
2012-11-07 11:08:18 -04:00
|
|
|
#include <AP_Buffer.h>
|
2013-08-29 02:04:17 -03:00
|
|
|
#include <AP_Notify.h>
|
2013-09-12 22:46:10 -03:00
|
|
|
#include <AP_Vehicle.h>
|
2013-08-29 02:04:17 -03:00
|
|
|
#include <DataFlash.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
#include <AP_HAL_AVR.h>
|
2012-12-18 06:27:50 -04:00
|
|
|
#include <AP_HAL_AVR_SITL.h>
|
|
|
|
#include <AP_HAL_Empty.h>
|
|
|
|
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2014-02-14 03:34:22 -04:00
|
|
|
// INS and Baro declaration
|
2012-12-11 20:23:02 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
AP_InertialSensor_MPU6000 ins;
|
2014-02-14 03:34:22 -04:00
|
|
|
AP_Baro_MS5611 baro(&AP_Baro_MS5611::spi);
|
2012-12-11 20:23:02 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
2012-08-17 02:40:30 -03:00
|
|
|
AP_ADC_ADS7844 adc;
|
|
|
|
AP_InertialSensor_Oilpan ins( &adc );
|
2014-02-14 03:34:22 -04:00
|
|
|
AP_Baro_BMP085 baro;
|
2012-12-18 06:27:50 -04:00
|
|
|
#else
|
2013-09-28 06:34:00 -03:00
|
|
|
AP_InertialSensor_HIL ins;
|
2012-03-11 05:00:39 -03:00
|
|
|
#endif
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
AP_Compass_HMC5843 compass;
|
|
|
|
|
2014-03-31 05:11:11 -03:00
|
|
|
AP_GPS gps;
|
2012-03-23 02:27:37 -03:00
|
|
|
|
2012-03-11 05:00:39 -03:00
|
|
|
// choose which AHRS system to use
|
2014-03-31 05:11:11 -03:00
|
|
|
AP_AHRS_DCM ahrs(ins, baro, gps);
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2013-05-02 02:09:05 -03:00
|
|
|
AP_Baro_HIL barometer;
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
#define HIGH 1
|
|
|
|
#define LOW 0
|
|
|
|
|
2012-03-03 00:49:38 -04:00
|
|
|
void setup(void)
|
|
|
|
{
|
|
|
|
|
|
|
|
#ifdef APM2_HARDWARE
|
2012-08-17 02:40:30 -03:00
|
|
|
// we need to stop the barometer from holding the SPI bus
|
2012-11-14 12:10:15 -04:00
|
|
|
hal.gpio->pinMode(40, GPIO_OUTPUT);
|
|
|
|
hal.gpio->write(40, HIGH);
|
2012-03-03 00:49:38 -04:00
|
|
|
#endif
|
|
|
|
|
2012-11-29 07:57:30 -04:00
|
|
|
ins.init(AP_InertialSensor::COLD_START,
|
2013-09-19 05:32:45 -03:00
|
|
|
AP_InertialSensor::RATE_100HZ);
|
|
|
|
ins.init_accel();
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
ahrs.init();
|
2012-07-28 02:27:26 -03:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
if( compass.init() ) {
|
2012-11-14 12:10:15 -04:00
|
|
|
hal.console->printf("Enabling compass\n");
|
2012-08-17 02:40:30 -03:00
|
|
|
ahrs.set_compass(&compass);
|
|
|
|
} else {
|
2012-11-14 12:10:15 -04:00
|
|
|
hal.console->printf("No compass detected\n");
|
2012-08-17 02:40:30 -03:00
|
|
|
}
|
2014-03-31 05:11:11 -03:00
|
|
|
gps.init(NULL);
|
2012-03-03 00:49:38 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop(void)
|
|
|
|
{
|
2012-08-17 02:40:30 -03:00
|
|
|
static uint16_t counter;
|
|
|
|
static uint32_t last_t, last_print, last_compass;
|
2012-11-14 12:10:15 -04:00
|
|
|
uint32_t now = hal.scheduler->micros();
|
2012-08-17 02:40:30 -03:00
|
|
|
float heading = 0;
|
|
|
|
|
|
|
|
if (last_t == 0) {
|
|
|
|
last_t = now;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
last_t = now;
|
|
|
|
|
|
|
|
if (now - last_compass > 100*1000UL &&
|
|
|
|
compass.read()) {
|
|
|
|
heading = compass.calculate_heading(ahrs.get_dcm_matrix());
|
|
|
|
// read compass at 10Hz
|
|
|
|
last_compass = now;
|
2012-03-23 02:27:37 -03:00
|
|
|
#if WITH_GPS
|
2012-08-17 02:40:30 -03:00
|
|
|
g_gps->update();
|
2012-03-23 02:27:37 -03:00
|
|
|
#endif
|
2012-08-17 02:40:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
ahrs.update();
|
|
|
|
counter++;
|
|
|
|
|
2012-11-14 12:10:15 -04:00
|
|
|
if (now - last_print >= 100000 /* 100ms : 10hz */) {
|
2012-08-17 02:40:30 -03:00
|
|
|
Vector3f drift = ahrs.get_gyro_drift();
|
2012-11-14 12:10:15 -04:00
|
|
|
hal.console->printf_P(
|
|
|
|
PSTR("r:%4.1f p:%4.1f y:%4.1f "
|
|
|
|
"drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n"),
|
2012-08-17 02:40:30 -03:00
|
|
|
ToDeg(ahrs.roll),
|
|
|
|
ToDeg(ahrs.pitch),
|
|
|
|
ToDeg(ahrs.yaw),
|
|
|
|
ToDeg(drift.x),
|
|
|
|
ToDeg(drift.y),
|
|
|
|
ToDeg(drift.z),
|
|
|
|
compass.use_for_yaw() ? ToDeg(heading) : 0.0,
|
|
|
|
(1.0e6*counter)/(now-last_print));
|
|
|
|
last_print = now;
|
|
|
|
counter = 0;
|
|
|
|
}
|
2012-03-03 00:49:38 -04:00
|
|
|
}
|
2012-11-14 12:10:15 -04:00
|
|
|
|
|
|
|
AP_HAL_MAIN();
|