2012-03-03 00:49:38 -04:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
|
|
|
|
//
|
2012-03-11 05:00:39 -03:00
|
|
|
// Simple test for the AP_AHRS interface
|
2012-03-03 00:49:38 -04:00
|
|
|
//
|
|
|
|
|
|
|
|
#include <FastSerial.h>
|
|
|
|
#include <SPI.h>
|
|
|
|
#include <I2C.h>
|
|
|
|
#include <Arduino_Mega_ISR_Registry.h>
|
|
|
|
#include <AP_PeriodicProcess.h>
|
|
|
|
#include <AP_InertialSensor.h>
|
|
|
|
#include <AP_ADC.h>
|
|
|
|
#include <AP_IMU.h>
|
|
|
|
#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_Math.h>
|
2012-09-13 04:44:39 -03:00
|
|
|
#include <AP_AnalogSource.h>
|
|
|
|
#include <AP_AnalogSource_Arduino.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_Compass.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 <DataFlash.h>
|
|
|
|
#include <APM_RC.h>
|
|
|
|
#include <GCS_MAVLink.h>
|
2012-03-22 07:13:26 -03:00
|
|
|
#include <Filter.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
// uncomment this for a APM2 board
|
2012-07-28 02:27:26 -03:00
|
|
|
#define APM2_HARDWARE
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-03-23 02:27:37 -03:00
|
|
|
#define WITH_GPS 0
|
|
|
|
|
|
|
|
FastSerialPort0(Serial);
|
|
|
|
FastSerialPort1(Serial1);
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
Arduino_Mega_ISR_Registry isr_registry;
|
2012-08-17 02:40:30 -03:00
|
|
|
AP_TimerProcess scheduler;
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
#ifdef DESKTOP_BUILD
|
2012-08-17 02:40:30 -03:00
|
|
|
AP_Compass_HIL compass;
|
2012-03-03 00:49:38 -04:00
|
|
|
#else
|
|
|
|
AP_Compass_HMC5843 compass;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifdef APM2_HARDWARE
|
2012-09-28 07:21:59 -03:00
|
|
|
AP_InertialSensor_MPU6000 ins;
|
2012-03-03 00:49:38 -04:00
|
|
|
# else
|
2012-08-17 02:40:30 -03:00
|
|
|
AP_ADC_ADS7844 adc;
|
|
|
|
AP_InertialSensor_Oilpan ins( &adc );
|
2012-03-11 05:00:39 -03:00
|
|
|
#endif
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
static GPS *g_gps;
|
|
|
|
|
2012-03-23 02:27:37 -03:00
|
|
|
AP_GPS_Auto g_gps_driver(&Serial1, &g_gps);
|
|
|
|
|
2012-03-03 00:49:38 -04:00
|
|
|
AP_IMU_INS imu(&ins);
|
2012-03-11 05:00:39 -03:00
|
|
|
|
|
|
|
// choose which AHRS system to use
|
2012-03-23 02:27:37 -03:00
|
|
|
AP_AHRS_DCM ahrs(&imu, g_gps);
|
|
|
|
//AP_AHRS_Quaternion ahrs(&imu, g_gps);
|
2012-07-28 02:27:26 -03:00
|
|
|
//AP_AHRS_MPU6000 ahrs(&imu, g_gps, &ins); // only works with APM2
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
AP_Baro_BMP085_HIL barometer;
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
|
|
|
|
#ifdef APM2_HARDWARE
|
2012-08-17 02:40:30 -03:00
|
|
|
# define A_LED_PIN 27
|
|
|
|
# define C_LED_PIN 25
|
|
|
|
# define LED_ON LOW
|
|
|
|
# define LED_OFF HIGH
|
|
|
|
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
|
2012-03-03 00:49:38 -04:00
|
|
|
#else
|
2012-08-17 02:40:30 -03:00
|
|
|
# define A_LED_PIN 37
|
|
|
|
# define C_LED_PIN 35
|
|
|
|
# define LED_ON HIGH
|
|
|
|
# define LED_OFF LOW
|
|
|
|
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
2012-03-03 00:49:38 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
static void flash_leds(bool on)
|
|
|
|
{
|
2012-08-17 02:40:30 -03:00
|
|
|
digitalWrite(A_LED_PIN, on ? LED_OFF : LED_ON);
|
|
|
|
digitalWrite(C_LED_PIN, on ? LED_ON : LED_OFF);
|
2012-03-03 00:49:38 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void setup(void)
|
|
|
|
{
|
2012-08-17 02:40:30 -03:00
|
|
|
Serial.begin(115200);
|
|
|
|
Serial.println("Starting up...");
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
#ifndef DESKTOP_BUILD
|
2012-08-17 02:40:30 -03:00
|
|
|
I2c.begin();
|
|
|
|
I2c.timeOut(5);
|
|
|
|
I2c.setSpeed(true);
|
2012-03-03 00:49:38 -04:00
|
|
|
#endif
|
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
SPI.begin();
|
|
|
|
SPI.setClockDivider(SPI_CLOCK_DIV16);
|
2012-03-03 00:49:38 -04:00
|
|
|
|
|
|
|
#ifdef APM2_HARDWARE
|
2012-08-17 02:40:30 -03:00
|
|
|
// we need to stop the barometer from holding the SPI bus
|
|
|
|
pinMode(40, OUTPUT);
|
|
|
|
digitalWrite(40, HIGH);
|
2012-03-03 00:49:38 -04:00
|
|
|
#endif
|
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
isr_registry.init();
|
|
|
|
scheduler.init(&isr_registry);
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
imu.init(IMU::COLD_START, delay, flash_leds, &scheduler);
|
|
|
|
imu.init_accel(delay, flash_leds);
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
compass.set_orientation(MAG_ORIENTATION);
|
|
|
|
ahrs.init();
|
2012-07-28 02:27:26 -03:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
if( compass.init() ) {
|
|
|
|
Serial.printf("Enabling compass\n");
|
|
|
|
ahrs.set_compass(&compass);
|
|
|
|
} else {
|
|
|
|
Serial.printf("No compass detected\n");
|
|
|
|
}
|
|
|
|
g_gps = &g_gps_driver;
|
2012-03-23 02:27:37 -03:00
|
|
|
#if WITH_GPS
|
2012-08-17 02:40:30 -03:00
|
|
|
g_gps->init();
|
2012-03-23 02:27:37 -03:00
|
|
|
#endif
|
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;
|
|
|
|
uint32_t now = micros();
|
|
|
|
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++;
|
|
|
|
|
|
|
|
if (now - last_print >= 0.5e6) {
|
|
|
|
Vector3f drift = ahrs.get_gyro_drift();
|
|
|
|
Serial.printf_P(PSTR("r:%4.1f p:%4.1f y:%4.1f drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n"),
|
|
|
|
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
|
|
|
}
|