mirror of https://github.com/ArduPilot/ardupilot
AC_PrecLand: correct include paths
This commit is contained in:
parent
c06593f987
commit
bf08fc317c
|
@ -1,9 +1,9 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#include <AP_HAL.h>
|
||||
#include <AC_PrecLand.h>
|
||||
#include <AC_PrecLand_Backend.h>
|
||||
#include <AC_PrecLand_Companion.h>
|
||||
#include <AC_PrecLand_IRLock.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AC_PrecLand.h"
|
||||
#include "AC_PrecLand_Backend.h"
|
||||
#include "AC_PrecLand_Companion.h"
|
||||
#include "AC_PrecLand_IRLock.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -2,10 +2,10 @@
|
|||
#ifndef __AC_PRECLAND_H__
|
||||
#define __AC_PRECLAND_H__
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AC_PI_2D.h> // PID library
|
||||
#include <AP_InertialNav.h> // Inertial Navigation library
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AC_PID/AC_PI_2D.h>
|
||||
#include <AP_InertialNav/AP_InertialNav.h>
|
||||
|
||||
// definitions
|
||||
#define AC_PRECLAND_SPEED_XY_DEFAULT 100.0f // maximum horizontal speed
|
||||
|
|
|
@ -2,11 +2,11 @@
|
|||
#ifndef __AC_PRECLAND_BACKEND_H__
|
||||
#define __AC_PRECLAND_BACKEND_H__
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AC_PID.h> // PID library
|
||||
#include <AP_InertialNav.h> // Inertial Navigation library
|
||||
#include <AC_PrecLand.h> // Precision Landing frontend
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AP_InertialNav/AP_InertialNav.h>
|
||||
#include "AC_PrecLand.h"
|
||||
|
||||
class AC_PrecLand_Backend
|
||||
{
|
||||
|
|
|
@ -1,12 +1,13 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#include <AP_HAL.h>
|
||||
#include <AC_PrecLand_Companion.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AC_PrecLand_Companion.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// Constructor
|
||||
AC_PrecLand_Companion::AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state)
|
||||
: AC_PrecLand_Backend(frontend, state)
|
||||
: AC_PrecLand_Backend(frontend, state),
|
||||
_chan(MAVLINK_COMM_0)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -2,9 +2,9 @@
|
|||
#ifndef __AC_PRECLAND_COMPANION_H__
|
||||
#define __AC_PRECLAND_COMPANION_H__
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AC_PrecLand_Backend.h> // Precision Landing backend
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "AC_PrecLand_Backend.h"
|
||||
|
||||
/*
|
||||
* AC_PrecLand_Companion - implements precision landing using target vectors provided
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#include <AP_HAL.h>
|
||||
#include <AC_PrecLand_IRLock.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AC_PrecLand_IRLock.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -2,10 +2,10 @@
|
|||
#ifndef __AC_PRECLAND_IRLOCK_H__
|
||||
#define __AC_PRECLAND_IRLOCK_H__
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AC_PrecLand_Backend.h> // Precision Landing backend
|
||||
#include <AP_IRLock.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AC_PrecLand/AC_PrecLand_Backend.h>
|
||||
#include <AP_IRLock/AP_IRLock.h>
|
||||
|
||||
/*
|
||||
* AC_PrecLand_IRLock - implements precision landing using target vectors provided
|
||||
|
|
Loading…
Reference in New Issue