mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: fix example sketch
AP_Airspeed: fix example sketch AP_Baro: fix example sketch AP_Declination: fix example sketch AP_Math: fix example sketch
This commit is contained in:
parent
93010fc79f
commit
4053346022
|
@ -11,7 +11,6 @@
|
|||
#include <AP_PeriodicProcess.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <AP_IMU.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_Math.h>
|
||||
|
@ -26,6 +25,7 @@
|
|||
#include <APM_RC.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
|
||||
// uncomment this for a APM2 board
|
||||
#define APM2_HARDWARE
|
||||
|
@ -55,12 +55,9 @@ static GPS *g_gps;
|
|||
|
||||
AP_GPS_Auto g_gps_driver(&Serial1, &g_gps);
|
||||
|
||||
AP_IMU_INS imu(&ins);
|
||||
|
||||
// choose which AHRS system to use
|
||||
AP_AHRS_DCM ahrs(&imu, g_gps);
|
||||
//AP_AHRS_Quaternion ahrs(&imu, g_gps);
|
||||
//AP_AHRS_MPU6000 ahrs(&imu, g_gps, &ins); // only works with APM2
|
||||
AP_AHRS_DCM ahrs(&ins, g_gps);
|
||||
//AP_AHRS_MPU6000 ahrs(&ins, g_gps); // only works with APM2
|
||||
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
|
||||
|
@ -109,8 +106,8 @@ void setup(void)
|
|||
isr_registry.init();
|
||||
scheduler.init(&isr_registry);
|
||||
|
||||
imu.init(IMU::COLD_START, delay, flash_leds, &scheduler);
|
||||
imu.init_accel(delay, flash_leds);
|
||||
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &scheduler);
|
||||
ins.init_accel(delay, flash_leds);
|
||||
|
||||
compass.set_orientation(MAG_ORIENTATION);
|
||||
ahrs.init();
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <AP_PeriodicProcess.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <AP_Airspeed.h>
|
||||
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
|
|
|
@ -13,6 +13,7 @@
|
|||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AverageFilter.h>
|
||||
#include <AP_Buffer.h>
|
||||
|
||||
#ifndef APM2_HARDWARE
|
||||
# define APM2_HARDWARE 0
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
#include <I2C.h>
|
||||
#include <SPI.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <AP_PeriodicProcess.h>
|
||||
#include <AP_Baro.h> // ArduPilot Mega ADC Library
|
||||
|
|
|
@ -6,12 +6,14 @@
|
|||
#include <AP_Math.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <I2C.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
// all of this is needed to build with SITL
|
||||
#include <DataFlash.h>
|
||||
#include <AP_Semaphore.h>
|
||||
#include <APM_RC.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
|
|
|
@ -25,6 +25,7 @@ FastSerialPort(Serial, 0);
|
|||
#include <AP_Declination.h>
|
||||
#include <AP_Semaphore.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <SITL.h>
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include <AP_Declination.h>
|
||||
#include <AP_Semaphore.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <SITL.h>
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
|
|
|
@ -25,6 +25,7 @@ FastSerialPort(Serial, 0);
|
|||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_Semaphore.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <SITL.h>
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
|
|
Loading…
Reference in New Issue