AP_WindVane.h 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Param/AP_Param.h>
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include <AP_SerialManager/AP_SerialManager.h>
  17. class AP_WindVane_Backend;
  18. class AP_WindVane
  19. {
  20. friend class AP_WindVane_Backend;
  21. friend class AP_WindVane_Home;
  22. friend class AP_WindVane_Analog;
  23. friend class AP_WindVane_SITL;
  24. friend class AP_WindVane_ModernDevice;
  25. friend class AP_WindVane_Airspeed;
  26. friend class AP_WindVane_RPM;
  27. friend class AP_WindVane_NMEA;
  28. public:
  29. AP_WindVane();
  30. /* Do not allow copies */
  31. AP_WindVane(const AP_WindVane &other) = delete;
  32. AP_WindVane &operator=(const AP_WindVane&) = delete;
  33. static AP_WindVane *get_singleton();
  34. // return true if wind vane is enabled
  35. bool enabled() const;
  36. // return true if wind speed is enabled
  37. bool wind_speed_enabled() const;
  38. // Initialize the Wind Vane object and prepare it for use
  39. void init(const AP_SerialManager& serial_manager);
  40. // update wind vane
  41. void update();
  42. // get the apparent wind direction in body-frame in radians, 0 = head to wind
  43. float get_apparent_wind_direction_rad() const {
  44. return wrap_PI(_direction_apparent_ef - AP::ahrs().yaw);
  45. }
  46. // get the true wind direction in radians, 0 = wind coming from north
  47. float get_true_wind_direction_rad() const { return _direction_true; }
  48. // Return apparent wind speed
  49. float get_apparent_wind_speed() const { return _speed_apparent; }
  50. // Return true wind speed
  51. float get_true_wind_speed() const { return _speed_true; }
  52. // record home heading for use as wind direction if no sensor is fitted
  53. void record_home_heading() { _home_heading = AP::ahrs().yaw; }
  54. // start calibration routine
  55. bool start_direction_calibration();
  56. bool start_speed_calibration();
  57. // send mavlink wind message
  58. void send_wind(mavlink_channel_t chan);
  59. // parameter block
  60. static const struct AP_Param::GroupInfo var_info[];
  61. private:
  62. // parameters
  63. AP_Int8 _direction_type; // type of windvane being used
  64. AP_Int8 _rc_in_no; // RC input channel to use
  65. AP_Int8 _dir_analog_pin; // analog pin connected to wind vane direction sensor
  66. AP_Float _dir_analog_volt_min; // minimum voltage read by windvane
  67. AP_Float _dir_analog_volt_max; // maximum voltage read by windvane
  68. AP_Float _dir_analog_bearing_offset; // angle offset when windvane is indicating a headwind, ie 0 degress relative to vehicle
  69. AP_Float _dir_analog_deadzone; // analog pot deadzone in degrees
  70. AP_Float _dir_filt_hz; // vane Low pass filter frequency
  71. AP_Int8 _calibration; // enter calibration
  72. AP_Float _dir_speed_cutoff; // vane cutoff wind speed
  73. AP_Int8 _speed_sensor_type; // wind speed sensor type
  74. AP_Int8 _speed_sensor_speed_pin; // speed sensor analog pin for reading speed
  75. AP_Float _speed_sensor_temp_pin; // speed sensor analog pin for reading temp, -1 if disable
  76. AP_Float _speed_sensor_voltage_offset; // analog speed zero wind voltage offset
  77. AP_Float _speed_filt_hz; // speed sensor low pass filter frequency
  78. AP_WindVane_Backend *_direction_driver;
  79. AP_WindVane_Backend *_speed_driver;
  80. // update wind speed sensor
  81. void update_apparent_wind_speed();
  82. // update apparent wind direction
  83. void update_apparent_wind_direction();
  84. // calculate true wind speed and direction from apparent wind
  85. void update_true_wind_speed_and_direction();
  86. // wind direction variables
  87. float _direction_apparent_ef; // wind's apparent direction in radians (0 = ahead of vehicle)
  88. float _direction_true; // wind's true direction in radians (0 = North)
  89. // wind speed variables
  90. float _speed_apparent; // wind's apparent speed in m/s
  91. float _speed_true; // wind's true estimated speed in m/s
  92. // heading in radians recorded when vehicle was armed
  93. float _home_heading;
  94. enum WindVaneType {
  95. WINDVANE_NONE = 0,
  96. WINDVANE_HOME_HEADING = 1,
  97. WINDVANE_PWM_PIN = 2,
  98. WINDVANE_ANALOG_PIN = 3,
  99. WINDVANE_NMEA = 4,
  100. WINDVANE_SITL = 10
  101. };
  102. enum Speed_type {
  103. WINDSPEED_NONE = 0,
  104. WINDSPEED_AIRSPEED = 1,
  105. WINDVANE_WIND_SENSOR_REV_P = 2,
  106. WINDSPEED_RPM = 3,
  107. WINDSPEED_NMEA = 4,
  108. WINDSPEED_SITL = 10
  109. };
  110. static AP_WindVane *_singleton;
  111. };
  112. namespace AP {
  113. AP_WindVane *windvane();
  114. };