diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 1b633f35db..7301257498 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -50,6 +50,8 @@ #include #include #include +#include + #include // Configuration @@ -97,7 +99,7 @@ public: private: // key aircraft parameters passed to multiple libraries - AP_Vehicle::MultiCopter aparm; + AP_MultiCopter aparm; // Global parameters are all contained within the 'g' class. Parameters g; diff --git a/Blimp/events.cpp b/Blimp/events.cpp index b3856bc960..cbd778cd6c 100644 --- a/Blimp/events.cpp +++ b/Blimp/events.cpp @@ -5,6 +5,7 @@ * boolean failsafe reflects the current state */ +#include bool Blimp::failsafe_option(FailsafeOption opt) const { diff --git a/Blimp/mode.cpp b/Blimp/mode.cpp index 2b18ff2915..511ac6be5b 100644 --- a/Blimp/mode.cpp +++ b/Blimp/mode.cpp @@ -5,6 +5,8 @@ * flight modes is in control_acro.cpp, control_stabilize.cpp, etc */ +#include + /* constructor for Mode object */ diff --git a/Blimp/mode_velocity.cpp b/Blimp/mode_velocity.cpp index b099089756..d4868ca222 100644 --- a/Blimp/mode_velocity.cpp +++ b/Blimp/mode_velocity.cpp @@ -3,6 +3,8 @@ * Init and run calls for velocity flight mode */ +#include + // Runs the main velocity controller void ModeVelocity::run() {