mirror of https://github.com/ArduPilot/ardupilot
Blimp: change namespace of MultiCopter and FixedWing params
this stops the libraries knowing anything about AP_Vehicle
This commit is contained in:
parent
9e69f8211e
commit
ea538641ea
|
@ -50,6 +50,8 @@
|
|||
#include <AC_PID/AC_PID_2D.h>
|
||||
#include <AC_PID/AC_PID_Basic.h>
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AP_Vehicle/AP_MultiCopter.h>
|
||||
|
||||
#include <Filter/NotchFilter.h>
|
||||
|
||||
// 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;
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
* boolean failsafe reflects the current state
|
||||
*/
|
||||
|
||||
#include <AP_Vehicle/AP_MultiCopter.h>
|
||||
|
||||
bool Blimp::failsafe_option(FailsafeOption opt) const
|
||||
{
|
||||
|
|
|
@ -5,6 +5,8 @@
|
|||
* flight modes is in control_acro.cpp, control_stabilize.cpp, etc
|
||||
*/
|
||||
|
||||
#include <AP_Vehicle/AP_MultiCopter.h>
|
||||
|
||||
/*
|
||||
constructor for Mode object
|
||||
*/
|
||||
|
|
|
@ -3,6 +3,8 @@
|
|||
* Init and run calls for velocity flight mode
|
||||
*/
|
||||
|
||||
#include <AP_Vehicle/AP_MultiCopter.h>
|
||||
|
||||
// Runs the main velocity controller
|
||||
void ModeVelocity::run()
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue