mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: add wind speed
This commit is contained in:
parent
ff4ef4968e
commit
bc1cf6a87a
|
@ -29,9 +29,11 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// by default use the airspeed pin for Vane
|
||||
#define WINDVANE_DEFAULT_PIN 15
|
||||
#define WINDVANE_DEFAULT_PIN 15 // default wind vane sensor analog pin
|
||||
#define WINDVANE_CALIBRATION_VOLT_DIFF_MIN 1.0f // calibration routine's min voltage difference required for success
|
||||
#define WINDSPEED_DEFAULT_SPEED_PIN 14 // default pin for reading speed from ModernDevice rev p wind sensor
|
||||
#define WINDSPEED_DEFAULT_TEMP_PIN 13 // default pin for reading temperature from ModernDevice rev p wind sensor
|
||||
#define WINDSPEED_DEFAULT_VOLT_OFFSET 1.346 // default voltage offset between speed and temp pins from ModernDevice rev p wind sensor
|
||||
|
||||
const AP_Param::GroupInfo AP_WindVane::var_info[] = {
|
||||
|
||||
|
@ -107,6 +109,52 @@ const AP_Param::GroupInfo AP_WindVane::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("ANA_DZ", 9, AP_WindVane, _analog_deadzone, 0),
|
||||
|
||||
// @Param: CUTOFF
|
||||
// @DisplayName: Wind vane cut off wind speed
|
||||
// @Description: Wind vane direction will be ignored when apparent wind speeds are below this value (if wind speed sensor is present). If the apparent wind is consistently below this value the vane will not work
|
||||
// @Units: m/s
|
||||
// @Increment: 0.1
|
||||
// @Range: 0 5
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("CUTOFF", 10, AP_WindVane, _vane_wind_speed_cutoff, 0),
|
||||
|
||||
// @Param: SPEED_TYPE
|
||||
// @DisplayName: Wind speed sensor Type
|
||||
// @Description: Wind speed sensor type
|
||||
// @Values: 0:None,1:Airspeed library,2:Moden Devices Wind Sensor rev. p
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED_TYPE", 11, AP_WindVane, _wind_speed_sensor_type, 0),
|
||||
|
||||
// @Param: SPEED_PIN1
|
||||
// @DisplayName: Wind vane speed sensor analog pin
|
||||
// @Description: Wind speed analog speed input pin for Modern Devices Wind Sensor rev. p
|
||||
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6,15:Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED_PIN1", 12, AP_WindVane, _wind_speed_sensor_speed_pin, WINDSPEED_DEFAULT_SPEED_PIN),
|
||||
|
||||
// @Param: SPEED_PIN2
|
||||
// @DisplayName: Wind vane speed sensor analog temp pin
|
||||
// @Description: Wind speed sensor analog temp input pin for Moden Devices Wind Sensor rev. p, set to -1 to diasble temp readings
|
||||
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6,15:Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED_PIN2", 13, AP_WindVane, _wind_speed_sensor_temp_pin, WINDSPEED_DEFAULT_TEMP_PIN),
|
||||
|
||||
// @Param: SPEED_OFS
|
||||
// @DisplayName: Wind speed sensor analog voltage offset
|
||||
// @Description: Wind sensor analog voltage offset at zero wind speed
|
||||
// @Units: V
|
||||
// @Increment: 0.01
|
||||
// @Range: 0 3.3
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED_OFS", 14, AP_WindVane, _wind_speed_sensor_voltage_offset, WINDSPEED_DEFAULT_VOLT_OFFSET),
|
||||
|
||||
// @Param: SPEED_FILT
|
||||
// @DisplayName: Wind speed low pass filter frequency
|
||||
// @Description: Wind speed low pass filter frequency, a value of -1 disables filter
|
||||
// @Units: Hz
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED_FILT", 15, AP_WindVane, _wind_speed_filt_hz, 0.5f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -141,6 +189,16 @@ void AP_WindVane::init()
|
|||
{
|
||||
// a pin for reading the Wind Vane voltage
|
||||
windvane_analog_source = hal.analogin->channel(_analog_pin_no);
|
||||
|
||||
// pins for ModernDevice rev p wind sensor
|
||||
wind_speed_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
|
||||
wind_speed_temp_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
|
||||
|
||||
// check that airspeed is enabled if it is selected as sensor type, if not revert to no wind speed sensor
|
||||
AP_Airspeed* airspeed = AP_Airspeed::get_singleton();
|
||||
if (_wind_speed_sensor_type == Speed_type::WINDSPEED_AIRSPEED && (airspeed == nullptr || !airspeed->enabled())) {
|
||||
_wind_speed_sensor_type.set(Speed_type::WINDSPEED_NONE);
|
||||
}
|
||||
}
|
||||
|
||||
// update wind vane, expected to be called at 20hz
|
||||
|
@ -154,7 +212,14 @@ void AP_WindVane::update()
|
|||
// check for calibration
|
||||
calibrate();
|
||||
|
||||
// read apparent wind speed
|
||||
update_apparent_wind_speed();
|
||||
|
||||
// read apparent wind direction (relies on wind speed above)
|
||||
update_apparent_wind_direction();
|
||||
|
||||
// calculate true wind speed and direction from apparent wind
|
||||
update_true_wind_speed_and_direction();
|
||||
}
|
||||
|
||||
// get the apparent wind direction in radians, 0 = head to wind
|
||||
|
@ -223,10 +288,92 @@ float AP_WindVane::read_SITL_direction_ef()
|
|||
|
||||
return atan2f(wind_vector_ef.y, wind_vector_ef.x);
|
||||
}
|
||||
|
||||
// read the apparent wind speed in m/s from SITL
|
||||
float AP_WindVane::read_wind_speed_SITL()
|
||||
{
|
||||
// temporarily store true speed and direction for easy access
|
||||
const float wind_speed = AP::sitl()->wind_speed_active;
|
||||
const float wind_dir_rad = radians(AP::sitl()->wind_direction_active);
|
||||
|
||||
// convert true wind speed and direction into a 2D vector
|
||||
Vector2f wind_vector_ef(cosf(wind_dir_rad) * wind_speed, sinf(wind_dir_rad) * wind_speed);
|
||||
|
||||
// add vehicle speed to get apparent wind vector
|
||||
wind_vector_ef.x += AP::sitl()->state.speedN;
|
||||
wind_vector_ef.y += AP::sitl()->state.speedE;
|
||||
|
||||
return wind_vector_ef.length();
|
||||
}
|
||||
#endif
|
||||
|
||||
// read wind speed from Modern Device rev p wind sensor
|
||||
// https://moderndevice.com/news/calibrating-rev-p-wind-sensor-new-regression/
|
||||
float AP_WindVane::read_wind_speed_ModernDevice()
|
||||
{
|
||||
float analog_voltage = 0.0f;
|
||||
|
||||
// only read temp pin if defined, sensor will do OK assuming constant temp
|
||||
float temp_ambient = 28.0f; // assume room temp (deg c), equations were generated at this temp in above data sheet
|
||||
if (is_positive(_wind_speed_sensor_temp_pin)) {
|
||||
wind_speed_temp_analog_source->set_pin(_wind_speed_sensor_temp_pin);
|
||||
analog_voltage = wind_speed_temp_analog_source->voltage_average();
|
||||
temp_ambient = (analog_voltage - 0.4f) / 0.0195f; // deg C
|
||||
// constrain to reasonable range to avoid deviating from calibration too much and potential divide by zero
|
||||
temp_ambient = constrain_float(temp_ambient, 10.0f, 40.0f);
|
||||
}
|
||||
|
||||
wind_speed_analog_source->set_pin(_wind_speed_sensor_speed_pin);
|
||||
analog_voltage = wind_speed_analog_source->voltage_average();
|
||||
|
||||
// apply voltage offset and make sure not negative
|
||||
// by default the voltage offset is the number provide by the manufacturer
|
||||
analog_voltage = analog_voltage - _wind_speed_sensor_voltage_offset;
|
||||
if (is_negative(analog_voltage)) {
|
||||
analog_voltage = 0.0f;
|
||||
}
|
||||
|
||||
// simplified equation from data sheet, converted from mph to m/s
|
||||
return 24.254896f * powf((analog_voltage / powf(temp_ambient, 0.115157f)), 3.009364f);
|
||||
}
|
||||
|
||||
// update the apparent wind speed
|
||||
void AP_WindVane::update_apparent_wind_speed()
|
||||
{
|
||||
float apparent_wind_speed_in = 0.0f;
|
||||
|
||||
switch (_wind_speed_sensor_type) {
|
||||
case WINDSPEED_AIRSPEED: {
|
||||
AP_Airspeed* airspeed = AP_Airspeed::get_singleton();
|
||||
if (airspeed != nullptr) {
|
||||
apparent_wind_speed_in = airspeed->get_airspeed();
|
||||
}
|
||||
break;
|
||||
}
|
||||
case WINDVANE_WIND_SENSOR_REV_P:
|
||||
apparent_wind_speed_in = read_wind_speed_ModernDevice();
|
||||
break;
|
||||
case WINDSPEED_SITL:
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
apparent_wind_speed_in = read_wind_speed_SITL();
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
_speed_apparent = 0.0f;
|
||||
return;
|
||||
}
|
||||
|
||||
// apply low pass filter if enabled
|
||||
if (is_positive(_wind_speed_filt_hz)) {
|
||||
wind_speed_filt.set_cutoff_frequency(_wind_speed_filt_hz);
|
||||
_speed_apparent = wind_speed_filt.apply(apparent_wind_speed_in, 0.02f);
|
||||
} else {
|
||||
_speed_apparent = apparent_wind_speed_in;
|
||||
}
|
||||
}
|
||||
|
||||
// calculate the apparent wind direction in radians, the wind comes from this direction, 0 = head to wind
|
||||
// expected to be called at 20hz
|
||||
// expected to be called at 20hz after apparent wind speed has been updated
|
||||
void AP_WindVane::update_apparent_wind_direction()
|
||||
{
|
||||
float apparent_angle_ef = 0.0f;
|
||||
|
@ -252,6 +399,11 @@ void AP_WindVane::update_apparent_wind_direction()
|
|||
break;
|
||||
}
|
||||
|
||||
// if not enough wind to move vane do not update the value
|
||||
if (_speed_apparent < _vane_wind_speed_cutoff){
|
||||
return;
|
||||
}
|
||||
|
||||
// apply low pass filter if enabled
|
||||
if (is_positive(_vane_filt_hz)) {
|
||||
wind_sin_filt.set_cutoff_frequency(_vane_filt_hz);
|
||||
|
@ -268,6 +420,41 @@ void AP_WindVane::update_apparent_wind_direction()
|
|||
_direction_apparent_ef = wrap_PI(_direction_apparent_ef);
|
||||
}
|
||||
|
||||
// calculate true wind speed and direction from apparent wind
|
||||
// https://en.wikipedia.org/wiki/Apparent_wind
|
||||
void AP_WindVane::update_true_wind_speed_and_direction()
|
||||
{
|
||||
// no wind speed sensor, so can't do true wind calcs
|
||||
if (_wind_speed_sensor_type == Speed_type::WINDSPEED_NONE) {
|
||||
_direction_absolute = _direction_apparent_ef;
|
||||
_speed_true = 0.0f;
|
||||
return;
|
||||
}
|
||||
|
||||
// if no vehicle speed, can't do calcs
|
||||
Vector3f veh_velocity;
|
||||
if (!AP::ahrs().get_velocity_NED(veh_velocity)) {
|
||||
// if no vehicle speed use apparent speed and direction directly
|
||||
_direction_absolute = _direction_apparent_ef;
|
||||
_speed_true = _speed_apparent;
|
||||
return;
|
||||
}
|
||||
|
||||
// convert apparent wind speed and direction to 2D vector in same frame as vehicle velocity
|
||||
const float wind_dir_180 = wrap_PI(_direction_apparent_ef + radians(180));
|
||||
const Vector2f wind_apparent_vec(cosf(wind_dir_180) * _speed_apparent, sinf(wind_dir_180) * _speed_apparent);
|
||||
|
||||
// add vehicle velocity
|
||||
Vector2f wind_true_vec = Vector2f(wind_apparent_vec.x + veh_velocity.x, wind_apparent_vec.y + veh_velocity.y);
|
||||
|
||||
// calculate true speed and direction
|
||||
_direction_absolute = wrap_PI(atan2f(wind_true_vec.y, wind_true_vec.x) - radians(180));
|
||||
_speed_true = wind_true_vec.length();
|
||||
|
||||
// make sure between -pi and pi
|
||||
_direction_absolute = wrap_PI(_direction_absolute);
|
||||
}
|
||||
|
||||
// calibrate windvane
|
||||
void AP_WindVane::calibrate()
|
||||
{
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <Filter/LowPassFilter.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
|
||||
class AP_WindVane
|
||||
{
|
||||
|
@ -52,6 +52,15 @@ public:
|
|||
// get the apparent wind direction in body-frame in radians, 0 = head to wind
|
||||
float get_apparent_wind_direction_rad() const;
|
||||
|
||||
// get the absolute wind direction in radians, 0 = wind coming from north
|
||||
float get_absolute_wind_direction_rad() const { return _direction_absolute; }
|
||||
|
||||
// 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; }
|
||||
|
||||
// record home heading
|
||||
void record_home_heading();
|
||||
|
||||
|
@ -72,11 +81,23 @@ private:
|
|||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
// read SITL's apparent wind direction in earth-frame in radians
|
||||
float read_SITL_direction_ef();
|
||||
|
||||
// read the apparent wind speed in m/s from SITL
|
||||
float read_wind_speed_SITL();
|
||||
#endif
|
||||
|
||||
// read wind speed from ModernDevice wind speed sensor rev p
|
||||
float read_wind_speed_ModernDevice();
|
||||
|
||||
// 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();
|
||||
|
||||
// calibrate
|
||||
void calibrate();
|
||||
|
||||
|
@ -90,25 +111,46 @@ private:
|
|||
AP_Float _vane_filt_hz; // vane Low pass filter frequency
|
||||
AP_Int8 _calibration; // enter calibration
|
||||
AP_Float _analog_deadzone; // analog pot deadzone in degrees
|
||||
AP_Float _vane_wind_speed_cutoff; // vane cutoff wind speed
|
||||
AP_Int8 _wind_speed_sensor_type; // wind speed sensor type
|
||||
AP_Int8 _wind_speed_sensor_speed_pin; // speed sensor analog pin for reading speed
|
||||
AP_Float _wind_speed_sensor_temp_pin; // speed sensor analog pin for reading temp, -1 if disable
|
||||
AP_Float _wind_speed_sensor_voltage_offset; // analog speed zero wind voltage offset
|
||||
AP_Float _wind_speed_filt_hz; // speed sensor low pass filter frequency
|
||||
|
||||
static AP_WindVane *_singleton;
|
||||
|
||||
// wind direction variables
|
||||
float _home_heading; // heading in radians recorded when vehicle was armed
|
||||
float _direction_apparent_ef; // wind's apparent direction in radians (0 = ahead of vehicle)
|
||||
float _direction_absolute; // wind's absolute direction in radians (0 = North)
|
||||
float _current_analog_voltage; // wind direction's latest analog voltage reading
|
||||
|
||||
// wind speed variables
|
||||
float _speed_apparent; // wind's apparent speed in m/s
|
||||
float _speed_true; // wind's true estimated speed in m/s
|
||||
|
||||
// calibration variables
|
||||
uint32_t _cal_start_ms = 0; // calibration start time in milliseconds after boot
|
||||
float _cal_volt_max; // maximum observed voltage during calibration
|
||||
float _cal_volt_min; // minimum observed voltage during calibration
|
||||
|
||||
enum Speed_type {
|
||||
WINDSPEED_NONE = 0,
|
||||
WINDSPEED_AIRSPEED = 1,
|
||||
WINDVANE_WIND_SENSOR_REV_P = 2,
|
||||
WINDSPEED_SITL = 10
|
||||
};
|
||||
|
||||
// pin for reading analog voltage
|
||||
AP_HAL::AnalogSource *windvane_analog_source;
|
||||
AP_HAL::AnalogSource *wind_speed_analog_source;
|
||||
AP_HAL::AnalogSource *wind_speed_temp_analog_source;
|
||||
|
||||
// low pass filters of direction
|
||||
LowPassFilterFloat wind_sin_filt = LowPassFilterFloat(2.0f);
|
||||
LowPassFilterFloat wind_cos_filt = LowPassFilterFloat(2.0f);
|
||||
LowPassFilterFloat wind_speed_filt = LowPassFilterFloat(2.0f);
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
Loading…
Reference in New Issue