mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AHRS: fixed build
AP_Airspeed.h is now needed to build AHRS
This commit is contained in:
parent
9d9c7b0455
commit
d0709443b4
@ -102,6 +102,7 @@ version 2.1 of the License, or (at your option) any later version.
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <AP_Airspeed.h> // needed for AHRS build
|
||||
#include <memcheck.h>
|
||||
|
||||
// Configuration
|
||||
|
@ -100,6 +100,7 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <AP_Airspeed.h> // needed for AHRS build
|
||||
#include <memcheck.h>
|
||||
|
||||
// Configuration
|
||||
|
@ -30,6 +30,8 @@
|
||||
#include <config.h>
|
||||
#include <Parameters.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <AP_AnalogSource.h>
|
||||
#include <AP_Airspeed.h>
|
||||
|
||||
// this sets up the parameter table, and sets the default values. This
|
||||
// must be the first AP_Param variable declared to ensure its
|
||||
|
Loading…
Reference in New Issue
Block a user