mirror of https://github.com/ArduPilot/ardupilot
Copter: use AP_FOLLOW_ENABLED
This commit is contained in:
parent
6251b3e3f3
commit
1c38be93c5
|
@ -27,6 +27,7 @@
|
|||
/// change in your local copy of APM_Config.h.
|
||||
///
|
||||
#include "APM_Config.h"
|
||||
#include <AP_Follow/AP_Follow_config.h>
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -189,7 +190,7 @@
|
|||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Follow - follow another vehicle or GCS
|
||||
#ifndef MODE_FOLLOW_ENABLED
|
||||
# define MODE_FOLLOW_ENABLED ENABLED
|
||||
# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -1718,6 +1718,7 @@ private:
|
|||
|
||||
};
|
||||
|
||||
#if AP_FOLLOW_ENABLED
|
||||
class ModeFollow : public ModeGuided {
|
||||
|
||||
public:
|
||||
|
@ -1747,6 +1748,7 @@ protected:
|
|||
|
||||
uint32_t last_log_ms; // system time of last time desired velocity was logging
|
||||
};
|
||||
#endif
|
||||
|
||||
class ModeZigZag : public Mode {
|
||||
|
||||
|
|
Loading…
Reference in New Issue