ardupilot/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
murata c808ee2f49 Global: To nullptr from NULL.
RC_Channel: To nullptr from NULL.

AC_Fence: To nullptr from NULL.

AC_Avoidance: To nullptr from NULL.

AC_PrecLand: To nullptr from NULL.

DataFlash: To nullptr from NULL.

SITL: To nullptr from NULL.

GCS_MAVLink: To nullptr from NULL.

DataFlash: To nullptr from NULL.

AP_Compass: To nullptr from NULL.

Global: To nullptr from NULL.

Global: To nullptr from NULL.
2016-11-02 16:04:47 -02:00

37 lines
583 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>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// sensor declaration
AP_InertialSensor ins;
AP_GPS gps;
AP_Baro baro;
AP_SerialManager serial_manager;
// choose which AHRS system to use
AP_AHRS_DCM ahrs(ins, baro, gps);
void setup(void)
{
serial_manager.init();
ins.init(100);
baro.init();
ahrs.init();
gps.init(nullptr, serial_manager);
}
void loop(void)
{
ahrs.update();
}
AP_HAL_MAIN();