From e93be25ed4d9f43337a4dfa53a5c3dbb38087d2f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 25 Feb 2022 16:06:30 +1100 Subject: [PATCH] AP_WindVane: include cleanups --- libraries/AP_WindVane/AP_WindVane.cpp | 6 ++++++ libraries/AP_WindVane/AP_WindVane.h | 8 ++++---- libraries/AP_WindVane/AP_WindVane_Analog.cpp | 5 +++++ libraries/AP_WindVane/AP_WindVane_Analog.h | 7 +------ libraries/AP_WindVane/AP_WindVane_Backend.cpp | 2 ++ libraries/AP_WindVane/AP_WindVane_Backend.h | 3 --- libraries/AP_WindVane/AP_WindVane_Home.cpp | 2 ++ libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp | 2 ++ libraries/AP_WindVane/AP_WindVane_ModernDevice.h | 1 - libraries/AP_WindVane/AP_WindVane_SITL.cpp | 3 +++ 10 files changed, 25 insertions(+), 14 deletions(-) diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index dba378495c..186394a5e4 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -23,7 +23,9 @@ #include "AP_WindVane_SITL.h" #include "AP_WindVane_NMEA.h" +#include #include +#include const AP_Param::GroupInfo AP_WindVane::var_info[] = { @@ -369,6 +371,10 @@ void AP_WindVane::update() } +void AP_WindVane::record_home_heading() +{ + _home_heading = AP::ahrs().yaw; +} // to start direction calibration from mavlink or other bool AP_WindVane::start_direction_calibration() diff --git a/libraries/AP_WindVane/AP_WindVane.h b/libraries/AP_WindVane/AP_WindVane.h index c4cbfaae12..ebc9adb476 100644 --- a/libraries/AP_WindVane/AP_WindVane.h +++ b/libraries/AP_WindVane/AP_WindVane.h @@ -15,8 +15,8 @@ #pragma once #include -#include -#include +#include +#include #ifndef WINDVANE_DEFAULT_PIN #define WINDVANE_DEFAULT_PIN -1 // default wind vane sensor analog pin @@ -58,7 +58,7 @@ public: bool wind_speed_enabled() const; // Initialize the Wind Vane object and prepare it for use - void init(const AP_SerialManager& serial_manager); + void init(const class AP_SerialManager& serial_manager); // update wind vane void update(); @@ -88,7 +88,7 @@ public: Sailboat_Tack get_current_tack() const { return _current_tack; } // record home heading for use as wind direction if no sensor is fitted - void record_home_heading() { _home_heading = AP::ahrs().yaw; } + void record_home_heading(); // start calibration routine bool start_direction_calibration(); diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.cpp b/libraries/AP_WindVane/AP_WindVane_Analog.cpp index ecf38c5dad..6e78c8c561 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Analog.cpp @@ -15,6 +15,11 @@ #include "AP_WindVane_Analog.h" +#include +#include + +extern const AP_HAL::HAL& hal; + #define WINDVANE_CALIBRATION_VOLT_DIFF_MIN 1.0f // calibration routine's min voltage difference required for success // constructor diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.h b/libraries/AP_WindVane/AP_WindVane_Analog.h index eed943835c..017266b0be 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.h +++ b/libraries/AP_WindVane/AP_WindVane_Analog.h @@ -16,11 +16,6 @@ #include "AP_WindVane_Backend.h" -#include -#include - -extern const AP_HAL::HAL& hal; - class AP_WindVane_Analog : public AP_WindVane_Backend { public: @@ -33,7 +28,7 @@ public: private: // pin for reading analog voltage - AP_HAL::AnalogSource *_dir_analog_source; + class AP_HAL::AnalogSource *_dir_analog_source; float _current_analog_voltage; uint32_t _cal_start_ms = 0; diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.cpp b/libraries/AP_WindVane/AP_WindVane_Backend.cpp index 02e041a252..39f9ac9ed7 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Backend.cpp @@ -16,6 +16,8 @@ #include "AP_WindVane.h" #include "AP_WindVane_Backend.h" +#include + // base class constructor. AP_WindVane_Backend::AP_WindVane_Backend(AP_WindVane &frontend) : _frontend(frontend) diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.h b/libraries/AP_WindVane/AP_WindVane_Backend.h index c2319acfba..e347de4972 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.h +++ b/libraries/AP_WindVane/AP_WindVane_Backend.h @@ -16,9 +16,6 @@ #include "AP_WindVane.h" -#include -#include - class AP_WindVane_Backend { public: diff --git a/libraries/AP_WindVane/AP_WindVane_Home.cpp b/libraries/AP_WindVane/AP_WindVane_Home.cpp index 64ed706402..042d4ca0c1 100644 --- a/libraries/AP_WindVane/AP_WindVane_Home.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Home.cpp @@ -15,6 +15,8 @@ #include "AP_WindVane_Home.h" +#include + void AP_WindVane_Home::update_direction() { float direction_apparent_ef = _frontend._home_heading; diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp index 402f3b9f07..e273601a43 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp @@ -17,6 +17,8 @@ // read wind speed from Modern Device rev p wind sensor // https://moderndevice.com/news/calibrating-rev-p-wind-sensor-new-regression/ +#include + // constructor AP_WindVane_ModernDevice::AP_WindVane_ModernDevice(AP_WindVane &frontend) : AP_WindVane_Backend(frontend) diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.h b/libraries/AP_WindVane/AP_WindVane_ModernDevice.h index 66b2e8c5c2..bb05cb215a 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.h +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.h @@ -16,7 +16,6 @@ #include "AP_WindVane_Backend.h" -#include #include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_WindVane/AP_WindVane_SITL.cpp b/libraries/AP_WindVane/AP_WindVane_SITL.cpp index 936ad2c63e..c853185b97 100644 --- a/libraries/AP_WindVane/AP_WindVane_SITL.cpp +++ b/libraries/AP_WindVane/AP_WindVane_SITL.cpp @@ -17,6 +17,9 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#include + void AP_WindVane_SITL::update_direction() { if (_frontend._direction_type == _frontend.WindVaneType::WINDVANE_SITL_TRUE) {