mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_Fence: always declare AC_PolyFenceItem
This commit is contained in:
parent
fc2bc2822e
commit
fb86318848
@ -1,15 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "AC_Fence_config.h"
|
#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>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
||||||
|
|
||||||
#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 1
|
|
||||||
|
|
||||||
// CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in
|
// CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in
|
||||||
// metres. This was a bug, and CIRCLE_INCLUSION was created to store
|
// metres. This was a bug, and CIRCLE_INCLUSION was created to store
|
||||||
@ -41,6 +33,14 @@ public:
|
|||||||
float radius;
|
float radius;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if AP_FENCE_ENABLED
|
||||||
|
|
||||||
|
#include <AP_Common/AP_Common.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
|
|
||||||
|
#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 1
|
||||||
|
|
||||||
class AC_PolyFence_loader
|
class AC_PolyFence_loader
|
||||||
{
|
{
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user