Blimp: change namespace of MultiCopter and FixedWing params

this stops the libraries knowing anything about AP_Vehicle
This commit is contained in:
Peter Barker 2022-09-30 09:10:41 +10:00 committed by Andrew Tridgell
parent 9e69f8211e
commit ea538641ea
4 changed files with 8 additions and 1 deletions

View File

@ -50,6 +50,8 @@
#include <AC_PID/AC_PID_2D.h> #include <AC_PID/AC_PID_2D.h>
#include <AC_PID/AC_PID_Basic.h> #include <AC_PID/AC_PID_Basic.h>
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
#include <AP_Vehicle/AP_MultiCopter.h>
#include <Filter/NotchFilter.h> #include <Filter/NotchFilter.h>
// Configuration // Configuration
@ -97,7 +99,7 @@ public:
private: private:
// key aircraft parameters passed to multiple libraries // key aircraft parameters passed to multiple libraries
AP_Vehicle::MultiCopter aparm; AP_MultiCopter aparm;
// Global parameters are all contained within the 'g' class. // Global parameters are all contained within the 'g' class.
Parameters g; Parameters g;

View File

@ -5,6 +5,7 @@
* boolean failsafe reflects the current state * boolean failsafe reflects the current state
*/ */
#include <AP_Vehicle/AP_MultiCopter.h>
bool Blimp::failsafe_option(FailsafeOption opt) const bool Blimp::failsafe_option(FailsafeOption opt) const
{ {

View File

@ -5,6 +5,8 @@
* flight modes is in control_acro.cpp, control_stabilize.cpp, etc * flight modes is in control_acro.cpp, control_stabilize.cpp, etc
*/ */
#include <AP_Vehicle/AP_MultiCopter.h>
/* /*
constructor for Mode object constructor for Mode object
*/ */

View File

@ -3,6 +3,8 @@
* Init and run calls for velocity flight mode * Init and run calls for velocity flight mode
*/ */
#include <AP_Vehicle/AP_MultiCopter.h>
// Runs the main velocity controller // Runs the main velocity controller
void ModeVelocity::run() void ModeVelocity::run()
{ {