ardupilot/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

90 lines
2.0 KiB
C++
Raw Normal View History

2013-05-29 20:54:53 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
// Simple test for the AP_AHRS interface
//
#include <AP_ADC/AP_ADC.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
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
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
// choose which AHRS system to use
2014-03-31 05:11:11 -03:00
AP_AHRS_DCM ahrs(ins, baro, gps);
2012-11-14 12:10:15 -04:00
#define HIGH 1
#define LOW 0
void setup(void)
{
ins.init(AP_InertialSensor::RATE_100HZ);
ahrs.init();
2015-02-03 02:56:54 -04:00
serial_manager.init();
if( compass.init() ) {
2012-11-14 12:10:15 -04:00
hal.console->printf("Enabling compass\n");
ahrs.set_compass(&compass);
} else {
2012-11-14 12:10:15 -04:00
hal.console->printf("No compass detected\n");
}
2015-02-03 02:56:54 -04:00
gps.init(NULL, serial_manager);
}
void loop(void)
{
static uint16_t counter;
static uint32_t last_t, last_print, last_compass;
uint32_t now = AP_HAL::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
g_gps->update();
2012-03-23 02:27:37 -03:00
#endif
}
ahrs.update();
counter++;
2012-11-14 12:10:15 -04:00
if (now - last_print >= 100000 /* 100ms : 10hz */) {
Vector3f drift = ahrs.get_gyro_drift();
hal.console->printf(
"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.0f,
(1.0e6f*counter)/(now-last_print));
last_print = now;
counter = 0;
}
}
2012-11-14 12:10:15 -04:00
AP_HAL_MAIN();