2018-08-21 23:45:56 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2022-02-25 01:06:30 -04:00
|
|
|
#include <Filter/Filter.h>
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
2019-05-09 21:14:18 -03:00
|
|
|
|
2021-07-14 22:44:02 -03:00
|
|
|
#ifndef WINDVANE_DEFAULT_PIN
|
|
|
|
#define WINDVANE_DEFAULT_PIN -1 // default wind vane sensor analog pin
|
|
|
|
#endif
|
|
|
|
#ifndef WINDSPEED_DEFAULT_SPEED_PIN
|
|
|
|
#define WINDSPEED_DEFAULT_SPEED_PIN -1 // default pin for reading speed from ModernDevice rev p wind sensor
|
|
|
|
#endif
|
|
|
|
#ifndef WINDSPEED_DEFAULT_TEMP_PIN
|
|
|
|
#define WINDSPEED_DEFAULT_TEMP_PIN -1 // default pin for reading temperature from ModernDevice rev p wind sensor
|
|
|
|
#endif
|
2019-09-17 19:56:16 -03:00
|
|
|
#define WINDSPEED_DEFAULT_VOLT_OFFSET 1.346f // default voltage offset between speed and temp pins from ModernDevice rev p wind sensor
|
|
|
|
|
2019-05-09 21:14:18 -03:00
|
|
|
class AP_WindVane_Backend;
|
2018-08-21 23:45:56 -03:00
|
|
|
|
|
|
|
class AP_WindVane
|
|
|
|
{
|
2019-05-09 21:14:18 -03:00
|
|
|
friend class AP_WindVane_Backend;
|
|
|
|
friend class AP_WindVane_Home;
|
|
|
|
friend class AP_WindVane_Analog;
|
|
|
|
friend class AP_WindVane_SITL;
|
|
|
|
friend class AP_WindVane_ModernDevice;
|
|
|
|
friend class AP_WindVane_Airspeed;
|
|
|
|
friend class AP_WindVane_RPM;
|
2019-05-28 18:31:34 -03:00
|
|
|
friend class AP_WindVane_NMEA;
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2019-05-28 18:31:34 -03:00
|
|
|
public:
|
2018-08-21 23:45:56 -03:00
|
|
|
AP_WindVane();
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_WindVane);
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2018-09-26 08:10:40 -03:00
|
|
|
static AP_WindVane *get_singleton();
|
2018-08-21 23:45:56 -03:00
|
|
|
|
|
|
|
// return true if wind vane is enabled
|
|
|
|
bool enabled() const;
|
|
|
|
|
2019-05-27 14:17:36 -03:00
|
|
|
// return true if wind speed is enabled
|
|
|
|
bool wind_speed_enabled() const;
|
|
|
|
|
2018-08-21 23:45:56 -03:00
|
|
|
// Initialize the Wind Vane object and prepare it for use
|
2022-02-25 01:06:30 -04:00
|
|
|
void init(const class AP_SerialManager& serial_manager);
|
2018-08-21 23:45:56 -03:00
|
|
|
|
|
|
|
// update wind vane
|
|
|
|
void update();
|
|
|
|
|
2018-09-26 08:10:40 -03:00
|
|
|
// get the apparent wind direction in body-frame in radians, 0 = head to wind
|
2021-04-10 17:22:53 -03:00
|
|
|
float get_apparent_wind_direction_rad() const { return _direction_apparent; }
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2019-07-28 18:10:21 -03:00
|
|
|
// get the true wind direction in radians, 0 = wind coming from north
|
|
|
|
float get_true_wind_direction_rad() const { return _direction_true; }
|
2018-10-06 01:51:10 -03:00
|
|
|
|
|
|
|
// Return apparent wind speed
|
|
|
|
float get_apparent_wind_speed() const { return _speed_apparent; }
|
|
|
|
|
|
|
|
// Return true wind speed
|
|
|
|
float get_true_wind_speed() const { return _speed_true; }
|
|
|
|
|
2021-04-10 17:22:53 -03:00
|
|
|
// Return the apparent wind angle used to determin the current tack
|
|
|
|
float get_tack_threshold_wind_dir_rad() const { return _direction_tack; }
|
|
|
|
|
2019-09-17 19:56:16 -03:00
|
|
|
// enum defining current tack
|
|
|
|
enum Sailboat_Tack {
|
|
|
|
TACK_PORT,
|
|
|
|
TACK_STARBOARD
|
|
|
|
};
|
|
|
|
|
|
|
|
// return the current tack
|
|
|
|
Sailboat_Tack get_current_tack() const { return _current_tack; }
|
|
|
|
|
2019-05-09 21:14:18 -03:00
|
|
|
// record home heading for use as wind direction if no sensor is fitted
|
2022-02-25 01:06:30 -04:00
|
|
|
void record_home_heading();
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2018-09-26 22:39:33 -03:00
|
|
|
// start calibration routine
|
2019-05-09 21:14:18 -03:00
|
|
|
bool start_direction_calibration();
|
|
|
|
bool start_speed_calibration();
|
2018-09-26 22:39:33 -03:00
|
|
|
|
2018-11-01 02:26:07 -03:00
|
|
|
// send mavlink wind message
|
2021-02-01 12:17:44 -04:00
|
|
|
void send_wind(mavlink_channel_t chan) const;
|
2018-11-01 02:26:07 -03:00
|
|
|
|
2018-08-21 23:45:56 -03:00
|
|
|
// parameter block
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
// parameters
|
2019-05-09 21:14:18 -03:00
|
|
|
AP_Int8 _direction_type; // type of windvane being used
|
2018-11-01 02:26:52 -03:00
|
|
|
AP_Int8 _dir_analog_pin; // analog pin connected to wind vane direction sensor
|
|
|
|
AP_Float _dir_analog_volt_min; // minimum voltage read by windvane
|
|
|
|
AP_Float _dir_analog_volt_max; // maximum voltage read by windvane
|
|
|
|
AP_Float _dir_analog_bearing_offset; // angle offset when windvane is indicating a headwind, ie 0 degress relative to vehicle
|
|
|
|
AP_Float _dir_analog_deadzone; // analog pot deadzone in degrees
|
|
|
|
AP_Float _dir_filt_hz; // vane Low pass filter frequency
|
2018-08-21 23:45:56 -03:00
|
|
|
AP_Int8 _calibration; // enter calibration
|
2018-11-01 02:26:52 -03:00
|
|
|
AP_Float _dir_speed_cutoff; // vane cutoff wind speed
|
|
|
|
AP_Int8 _speed_sensor_type; // wind speed sensor type
|
|
|
|
AP_Int8 _speed_sensor_speed_pin; // speed sensor analog pin for reading speed
|
|
|
|
AP_Float _speed_sensor_temp_pin; // speed sensor analog pin for reading temp, -1 if disable
|
|
|
|
AP_Float _speed_sensor_voltage_offset; // analog speed zero wind voltage offset
|
|
|
|
AP_Float _speed_filt_hz; // speed sensor low pass filter frequency
|
2021-04-10 17:22:53 -03:00
|
|
|
AP_Float _true_filt_hz; // true wind speed and direction low pass filter frequency
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2019-05-09 21:14:18 -03:00
|
|
|
AP_WindVane_Backend *_direction_driver;
|
|
|
|
AP_WindVane_Backend *_speed_driver;
|
|
|
|
|
|
|
|
// update wind speed sensor
|
|
|
|
void update_apparent_wind_speed();
|
|
|
|
|
|
|
|
// update apparent wind direction
|
|
|
|
void update_apparent_wind_direction();
|
|
|
|
|
|
|
|
// calculate true wind speed and direction from apparent wind
|
|
|
|
void update_true_wind_speed_and_direction();
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2021-04-10 17:22:53 -03:00
|
|
|
// assume true wind has not changed and calculate apparent wind
|
|
|
|
void update_apparent_wind_dir_from_true();
|
|
|
|
|
2018-08-21 23:45:56 -03:00
|
|
|
// wind direction variables
|
2021-04-10 17:22:53 -03:00
|
|
|
float _direction_apparent_raw; // wind's apparent direction in radians (0 = ahead of vehicle) in body frame
|
|
|
|
float _direction_apparent; // wind's apparent direction in radians (0 = ahead of vehicle) in body frame - filtered
|
|
|
|
float _direction_true_raw; // wind's true direction in radians (0 = North)
|
|
|
|
float _direction_true; // wind's true direction in radians (0 = North) - filtered
|
|
|
|
float _direction_tack; // filtered apparent wind used to determin the current tack
|
2021-06-06 05:41:33 -03:00
|
|
|
LowPassFilterFloat _direction_apparent_sin_filt{2.0f};
|
|
|
|
LowPassFilterFloat _direction_apparent_cos_filt{2.0f};
|
|
|
|
LowPassFilterFloat _direction_true_sin_filt{2.0f};
|
|
|
|
LowPassFilterFloat _direction_true_cos_filt{2.0f};
|
|
|
|
LowPassFilterFloat _tack_sin_filt{0.1f};
|
|
|
|
LowPassFilterFloat _tack_cos_filt{0.1f};
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2018-10-06 01:51:10 -03:00
|
|
|
// wind speed variables
|
2021-04-10 17:22:53 -03:00
|
|
|
float _speed_apparent_raw; // wind's apparent speed in m/s
|
|
|
|
float _speed_apparent; // wind's apparent speed in m/s - filtered
|
|
|
|
float _speed_true_raw; // wind's true estimated speed in m/s
|
|
|
|
float _speed_true; // wind's true estimated speed in m/s - filtered
|
2021-06-06 05:41:33 -03:00
|
|
|
LowPassFilterFloat _speed_apparent_filt{2.0f};
|
|
|
|
LowPassFilterFloat _speed_true_filt{2.0f};
|
2018-10-06 01:51:10 -03:00
|
|
|
|
2019-09-17 19:56:16 -03:00
|
|
|
// current tack
|
|
|
|
Sailboat_Tack _current_tack;
|
|
|
|
|
2019-05-09 21:14:18 -03:00
|
|
|
// heading in radians recorded when vehicle was armed
|
|
|
|
float _home_heading;
|
|
|
|
|
|
|
|
enum WindVaneType {
|
2019-05-28 18:31:34 -03:00
|
|
|
WINDVANE_NONE = 0,
|
|
|
|
WINDVANE_HOME_HEADING = 1,
|
|
|
|
WINDVANE_PWM_PIN = 2,
|
|
|
|
WINDVANE_ANALOG_PIN = 3,
|
|
|
|
WINDVANE_NMEA = 4,
|
2020-08-15 12:36:29 -03:00
|
|
|
WINDVANE_SITL_TRUE = 10,
|
|
|
|
WINDVANE_SITL_APPARENT = 11,
|
2019-05-09 21:14:18 -03:00
|
|
|
};
|
2018-08-21 23:45:56 -03:00
|
|
|
|
2018-10-06 01:51:10 -03:00
|
|
|
enum Speed_type {
|
|
|
|
WINDSPEED_NONE = 0,
|
|
|
|
WINDSPEED_AIRSPEED = 1,
|
|
|
|
WINDVANE_WIND_SENSOR_REV_P = 2,
|
2019-02-25 12:48:58 -04:00
|
|
|
WINDSPEED_RPM = 3,
|
2019-05-28 18:31:34 -03:00
|
|
|
WINDSPEED_NMEA = 4,
|
2020-08-15 12:36:29 -03:00
|
|
|
WINDSPEED_SITL_TRUE = 10,
|
|
|
|
WINDSPEED_SITL_APPARENT = 11,
|
2018-10-06 01:51:10 -03:00
|
|
|
};
|
|
|
|
|
2019-05-09 21:14:18 -03:00
|
|
|
static AP_WindVane *_singleton;
|
2018-08-21 23:45:56 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_WindVane *windvane();
|
|
|
|
};
|