mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SmartRTL: clean includes
This commit is contained in:
parent
3859daf131
commit
6dbe662941
@ -13,6 +13,8 @@
|
|||||||
|
|
||||||
#include "AP_SmartRTL.h"
|
#include "AP_SmartRTL.h"
|
||||||
|
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
@ -3,8 +3,6 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Common/Bitmask.h>
|
#include <AP_Common/Bitmask.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
#include <AP_Logger/AP_Logger.h>
|
|
||||||
|
|
||||||
// definitions and macros
|
// definitions and macros
|
||||||
#define SMARTRTL_ACCURACY_DEFAULT 2.0f // default _ACCURACY parameter value. Points will be no closer than this distance (in meters) together.
|
#define SMARTRTL_ACCURACY_DEFAULT 2.0f // default _ACCURACY parameter value. Points will be no closer than this distance (in meters) together.
|
||||||
|
Loading…
Reference in New Issue
Block a user