mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: move to config file and rename from AC_FENCE to AP_FENCE_ENABLED
This commit is contained in:
parent
1342fa4851
commit
9dc318f0cc
|
@ -1,11 +1,11 @@
|
|||
#include "AC_Fence.h"
|
||||
|
||||
#if AC_FENCE
|
||||
#if AP_FENCE_ENABLED
|
||||
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
#ifndef AC_FENCE_DUMMY_METHODS_ENABLED
|
||||
#define AC_FENCE_DUMMY_METHODS_ENABLED !(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub))
|
||||
#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub)))
|
||||
#endif
|
||||
|
||||
#if !AC_FENCE_DUMMY_METHODS_ENABLED
|
||||
|
@ -756,4 +756,4 @@ AC_Fence *fence()
|
|||
|
||||
}
|
||||
|
||||
#endif // AC_FENCE
|
||||
#endif // AP_FENCE_ENABLED
|
||||
|
|
|
@ -1,17 +1,15 @@
|
|||
#pragma once
|
||||
|
||||
#include "AC_Fence_config.h"
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AC_Fence/AC_PolyFence_loader.h>
|
||||
|
||||
#ifndef AC_FENCE
|
||||
#define AC_FENCE 1
|
||||
#endif
|
||||
|
||||
#if AC_FENCE
|
||||
|
||||
// bit masks for enabled fence types. Used for TYPE parameter
|
||||
#define AC_FENCE_TYPE_ALT_MAX 1 // high alt fence which usually initiates an RTL
|
||||
#define AC_FENCE_TYPE_CIRCLE 2 // circular horizontal fence (usually initiates an RTL)
|
||||
|
@ -231,4 +229,4 @@ namespace AP {
|
|||
AC_Fence *fence();
|
||||
};
|
||||
|
||||
#endif // AC_FENCE
|
||||
#endif // AP_FENCE_ENABLED
|
||||
|
|
|
@ -1,8 +1,11 @@
|
|||
#include "AC_PolyFence_loader.h"
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
#ifndef AC_FENCE_DUMMY_METHODS_ENABLED
|
||||
#define AC_FENCE_DUMMY_METHODS_ENABLED !(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub))
|
||||
#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub)))
|
||||
#endif
|
||||
|
||||
#if !AC_FENCE_DUMMY_METHODS_ENABLED
|
||||
|
@ -1698,3 +1701,4 @@ bool AC_PolyFence_loader::get_return_point(Vector2l &ret) { return false; }
|
|||
#endif
|
||||
|
||||
#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED
|
||||
#endif // AP_FENCE_ENABLED
|
||||
|
|
|
@ -1,5 +1,9 @@
|
|||
#pragma once
|
||||
|
||||
#include "AC_Fence_config.h"
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
@ -434,3 +438,5 @@ private:
|
|||
|
||||
uint16_t fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count);
|
||||
};
|
||||
|
||||
#endif // AP_FENCE_ENABLED
|
||||
|
|
Loading…
Reference in New Issue