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
|
|
|
//
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Progmem/AP_Progmem.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
|
|
|
#include <AP_ADC/AP_ADC.h>
|
|
|
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
|
|
|
#include <AP_Baro/AP_Baro.h> // ArduPilot Mega Barometer Library
|
|
|
|
#include <AP_GPS/AP_GPS.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_Compass/AP_Compass.h>
|
|
|
|
#include <AP_Declination/AP_Declination.h>
|
|
|
|
#include <AP_Airspeed/AP_Airspeed.h>
|
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
|
|
|
#include <StorageManager/StorageManager.h>
|
|
|
|
#include <AP_Terrain/AP_Terrain.h>
|
|
|
|
#include <Filter/Filter.h>
|
|
|
|
#include <SITL/SITL.h>
|
|
|
|
#include <AP_Buffer/AP_Buffer.h>
|
|
|
|
#include <AP_Notify/AP_Notify.h>
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
|
|
|
#include <DataFlash/DataFlash.h>
|
|
|
|
#include <AP_NavEKF/AP_NavEKF.h>
|
|
|
|
#include <AP_Rally/AP_Rally.h>
|
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
|
|
|
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
|
|
|
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
|
|
|
#include <AP_HAL_Linux/AP_HAL_Linux.h>
|
|
|
|
#include <AP_HAL_PX4/AP_HAL_PX4.h>
|
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
|
|
|
#include <AP_SerialManager/AP_SerialManager.h>
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
2012-12-18 06:27:50 -04:00
|
|
|
|
|
|
|
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
|
2014-10-15 23:53:49 -03:00
|
|
|
AP_InertialSensor ins;
|
2014-11-27 19:40:52 -04:00
|
|
|
|
2014-11-28 02:59:18 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
2015-01-26 15:17:39 -04:00
|
|
|
AP_ADC_ADS7844 apm1_adc;
|
2012-03-11 05:00:39 -03:00
|
|
|
#endif
|
2012-03-03 00:49:38 -04:00
|
|
|
|
2015-03-16 08:21:35 -03:00
|
|
|
Compass compass;
|
2012-11-14 12:10:15 -04:00
|
|
|
|
2014-03-31 05:11:11 -03:00
|
|
|
AP_GPS gps;
|
2015-01-05 07:28:44 -04:00
|
|
|
AP_Baro baro;
|
2015-02-03 02:56:54 -04:00
|
|
|
AP_SerialManager serial_manager;
|
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
|
|
|
|
|
|
|
|
|
|
|
|
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
|
2014-06-01 20:28:54 -03:00
|
|
|
hal.gpio->pinMode(40, HAL_HAL_GPIO_OUTPUT);
|
2012-11-14 12:10:15 -04:00
|
|
|
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);
|
2012-08-17 02:40:30 -03:00
|
|
|
ahrs.init();
|
2015-02-03 02:56:54 -04:00
|
|
|
serial_manager.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
|
|
|
}
|
2015-02-03 02:56:54 -04:00
|
|
|
gps.init(NULL, serial_manager);
|
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),
|
2015-04-24 00:25:12 -03:00
|
|
|
compass.use_for_yaw() ? ToDeg(heading) : 0.0f,
|
2015-05-02 06:36:15 -03:00
|
|
|
(1.0e6f*counter)/(now-last_print));
|
2012-08-17 02:40:30 -03:00
|
|
|
last_print = now;
|
|
|
|
counter = 0;
|
|
|
|
}
|
2012-03-03 00:49:38 -04:00
|
|
|
}
|
2012-11-14 12:10:15 -04:00
|
|
|
|
|
|
|
AP_HAL_MAIN();
|