mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: tidy includes
This commit is contained in:
parent
80c3415419
commit
3592132774
|
@ -24,9 +24,12 @@
|
|||
#include "AP_WindVane_NMEA.h"
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_Param::GroupInfo AP_WindVane::var_info[] = {
|
||||
|
||||
// @Param: TYPE
|
||||
|
|
|
@ -22,6 +22,10 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
#define WINDVANE_CALIBRATION_VOLT_DIFF_MIN 1.0f // calibration routine's min voltage difference required for success
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
AP_WindVane_Analog::AP_WindVane_Analog(AP_WindVane &frontend) :
|
||||
AP_WindVane_Backend(frontend)
|
||||
|
|
|
@ -17,8 +17,11 @@
|
|||
// read wind speed from Modern Device rev p wind sensor
|
||||
// https://moderndevice.com/news/calibrating-rev-p-wind-sensor-new-regression/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
AP_WindVane_ModernDevice::AP_WindVane_ModernDevice(AP_WindVane &frontend) :
|
||||
AP_WindVane_Backend(frontend)
|
||||
|
|
|
@ -16,10 +16,6 @@
|
|||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
class AP_WindVane_ModernDevice : public AP_WindVane_Backend
|
||||
{
|
||||
public:
|
||||
|
|
Loading…
Reference in New Issue