AC_Fence: add build_options.py option to remove fencepoint protocol

also gate more code on defines

Saves ~2kB
This commit is contained in:
Peter Barker 2023-08-07 15:15:39 +10:00 committed by Andrew Tridgell
parent 9212a24248
commit c300beae69
3 changed files with 4 additions and 6 deletions

View File

@ -9,3 +9,7 @@
#ifndef AP_FENCE_ENABLED
#define AP_FENCE_ENABLED 2
#endif
#ifndef AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT AP_FENCE_ENABLED
#endif

View File

@ -1221,7 +1221,6 @@ bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_
}
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
bool AC_PolyFence_loader::get_return_point(Vector2l &ret)
{
if (!check_indexed()) {
@ -1296,7 +1295,6 @@ bool AC_PolyFence_loader::get_return_point(Vector2l &ret)
return true;
}
#endif
AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::find_first_fence(const AC_PolyFenceType type) const
{

View File

@ -39,8 +39,6 @@ public:
#include <AP_Common/Location.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 1
class AC_PolyFence_loader
{
@ -174,12 +172,10 @@ public:
// call @10Hz to check for fence load being valid
void update();
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
// get_return_point - returns latitude/longitude of return point.
// This works with storage - the returned vector is absolute
// lat/lon.
bool get_return_point(Vector2l &ret) WARN_IF_UNUSED;
#endif
// return total number of fences - polygons and circles
uint16_t total_fence_count() const {