mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
c72c1de99e
See discussion here: https://github.com/ArduPilot/ardupilot/issues/7331 we were getting some uninitialised variables. While it only showed up in AP_SbusOut, it means we can't be sure it won't happen on other objects, so safest to remove the approach Thanks to assistance from Lucas, Peter and Francisco
40 lines
636 B
C++
40 lines
636 B
C++
//
|
|
// 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>
|
|
#include <AP_Module/AP_Module.h>
|
|
|
|
void setup();
|
|
void loop();
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|
|
|
// sensor declaration
|
|
static AP_InertialSensor ins;
|
|
static AP_GPS gps;
|
|
static AP_Baro baro;
|
|
static AP_SerialManager serial_manager;
|
|
|
|
// choose which AHRS system to use
|
|
static AP_AHRS_DCM ahrs{ins, baro, gps};
|
|
|
|
void setup(void)
|
|
{
|
|
serial_manager.init();
|
|
ins.init(100);
|
|
baro.init();
|
|
ahrs.init();
|
|
|
|
gps.init(serial_manager);
|
|
}
|
|
|
|
void loop(void)
|
|
{
|
|
ahrs.update();
|
|
}
|
|
|
|
AP_HAL_MAIN();
|