mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: include cleanups
This commit is contained in:
parent
7a19719a5e
commit
e93be25ed4
|
@ -23,7 +23,9 @@
|
|||
#include "AP_WindVane_SITL.h"
|
||||
#include "AP_WindVane_NMEA.h"
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
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()
|
||||
|
|
|
@ -15,8 +15,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <Filter/Filter.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
#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();
|
||||
|
|
|
@ -15,6 +15,11 @@
|
|||
|
||||
#include "AP_WindVane_Analog.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define WINDVANE_CALIBRATION_VOLT_DIFF_MIN 1.0f // calibration routine's min voltage difference required for success
|
||||
|
||||
// constructor
|
||||
|
|
|
@ -16,11 +16,6 @@
|
|||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
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;
|
||||
|
|
|
@ -16,6 +16,8 @@
|
|||
#include "AP_WindVane.h"
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
// base class constructor.
|
||||
AP_WindVane_Backend::AP_WindVane_Backend(AP_WindVane &frontend) :
|
||||
_frontend(frontend)
|
||||
|
|
|
@ -16,9 +16,6 @@
|
|||
|
||||
#include "AP_WindVane.h"
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <Filter/Filter.h>
|
||||
|
||||
class AP_WindVane_Backend
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -15,6 +15,8 @@
|
|||
|
||||
#include "AP_WindVane_Home.h"
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
void AP_WindVane_Home::update_direction()
|
||||
{
|
||||
float direction_apparent_ef = _frontend._home_heading;
|
||||
|
|
|
@ -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 <GCS_MAVLink/GCS.h>
|
||||
|
||||
// constructor
|
||||
AP_WindVane_ModernDevice::AP_WindVane_ModernDevice(AP_WindVane &frontend) :
|
||||
AP_WindVane_Backend(frontend)
|
||||
|
|
|
@ -16,7 +16,6 @@
|
|||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
|
|
@ -17,6 +17,9 @@
|
|||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
||||
#include <SITL/SITL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
void AP_WindVane_SITL::update_direction()
|
||||
{
|
||||
if (_frontend._direction_type == _frontend.WindVaneType::WINDVANE_SITL_TRUE) {
|
||||
|
|
Loading…
Reference in New Issue