APM:Libraries
ModuleTest.cpp
Go to the documentation of this file.
1 //
2 // Simple test for the AP_AHRS interface
3 //
4 
5 #include <AP_ADC/AP_ADC.h>
6 #include <AP_AHRS/AP_AHRS.h>
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Module/AP_Module.h>
9 
10 void setup();
11 void loop();
12 
14 
15 // sensor declaration
17 static AP_GPS gps;
18 static AP_Baro baro;
20 
21 // choose which AHRS system to use
22 static AP_AHRS_DCM ahrs{};
23 
24 void setup(void)
25 {
26  serial_manager.init();
27  ins.init(100);
28  baro.init();
29  ahrs.init();
30 
31  gps.init(serial_manager);
32 }
33 
34 void loop(void)
35 {
36  ahrs.update();
37 }
38 
39 AP_HAL_MAIN();
static AP_GPS gps
Definition: ModuleTest.cpp:17
Definition: AP_GPS.h:48
static AP_InertialSensor ins
Definition: ModuleTest.cpp:16
void update(bool skip_ins_update=false) override
Definition: AP_AHRS_DCM.cpp:50
virtual void init()
Definition: AP_AHRS.h:88
AP_HAL_MAIN()
void init(const AP_SerialManager &serial_manager)
Startup initialisation.
Definition: AP_GPS.cpp:279
void init(void)
Definition: AP_Baro.cpp:398
void loop()
Definition: ModuleTest.cpp:34
static AP_Baro baro
Definition: ModuleTest.cpp:18
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: ModuleTest.cpp:13
void setup()
Definition: ModuleTest.cpp:24
const HAL & get_HAL()
void init(uint16_t sample_rate_hz)
static AP_SerialManager serial_manager
Definition: ModuleTest.cpp:19
static AP_AHRS_DCM ahrs
Definition: ModuleTest.cpp:22