AC_Avoidance: tidy includes

This commit is contained in:
Peter Barker 2022-03-01 12:19:06 +11:00 committed by Andrew Tridgell
parent 73c6eabde2
commit 666ac39e31
5 changed files with 7 additions and 17 deletions

View File

@ -3,7 +3,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
/*
* BendyRuler avoidance algorithm for avoiding the polygon and circular fence and dynamic objects detected by the proximity sensor
@ -12,9 +11,7 @@ class AP_OABendyRuler {
public:
AP_OABendyRuler();
/* Do not allow copies */
AP_OABendyRuler(const AP_OABendyRuler &other) = delete;
AP_OABendyRuler &operator=(const AP_OABendyRuler&) = delete;
CLASS_NO_COPY(AP_OABendyRuler); /* Do not allow copies */
// send configuration info stored in front end parameters
void set_config(float margin_max) { _margin_max = MAX(margin_max, 0.0f); }

View File

@ -1,6 +1,6 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Semaphores.h>
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Param/AP_Param.h>
@ -10,9 +10,7 @@ public:
AP_OADatabase();
/* Do not allow copies */
AP_OADatabase(const AP_OADatabase &other) = delete;
AP_OADatabase &operator=(const AP_OADatabase&) = delete;
CLASS_NO_COPY(AP_OADatabase); /* Do not allow copies */
// get singleton instance
static AP_OADatabase *get_singleton() {

View File

@ -3,7 +3,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_OAVisGraph.h"
/*
@ -15,9 +14,7 @@ public:
AP_OADijkstra(AP_Int16 &options);
/* Do not allow copies */
AP_OADijkstra(const AP_OADijkstra &other) = delete;
AP_OADijkstra &operator=(const AP_OADijkstra&) = delete;
CLASS_NO_COPY(AP_OADijkstra); /* Do not allow copies */
// set fence margin (in meters) used when creating "safe positions" within the polygon fence
void set_fence_margin(float margin) { _polyfence_margin = MAX(margin, 0.0f); }

View File

@ -3,7 +3,8 @@
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Semaphores.h>
#include "AP_OABendyRuler.h"
#include "AP_OADijkstra.h"
#include "AP_OADatabase.h"

View File

@ -2,7 +2,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Common/AP_ExpandingArray.h>
#include <AP_HAL/AP_HAL.h>
/*
* Visibility graph used by Dijkstra's algorithm for path planning around fence, stay-out zones and moving obstacles
@ -11,9 +10,7 @@ class AP_OAVisGraph {
public:
AP_OAVisGraph();
/* Do not allow copies */
AP_OAVisGraph(const AP_OAVisGraph &other) = delete;
AP_OAVisGraph &operator=(const AP_OAVisGraph&) = delete;
CLASS_NO_COPY(AP_OAVisGraph); /* Do not allow copies */
// types of items held in graph
enum OAType : uint8_t {