AP_WindVane.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371
  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. #include "AP_WindVane.h"
  14. #include "AP_WindVane_Home.h"
  15. #include "AP_WindVane_Analog.h"
  16. #include "AP_WindVane_ModernDevice.h"
  17. #include "AP_WindVane_Airspeed.h"
  18. #include "AP_WindVane_RPM.h"
  19. #include "AP_WindVane_SITL.h"
  20. #include "AP_WindVane_NMEA.h"
  21. #define WINDVANE_DEFAULT_PIN 15 // default wind vane sensor analog pin
  22. #define WINDSPEED_DEFAULT_SPEED_PIN 14 // default pin for reading speed from ModernDevice rev p wind sensor
  23. #define WINDSPEED_DEFAULT_TEMP_PIN 13 // default pin for reading temperature from ModernDevice rev p wind sensor
  24. #define WINDSPEED_DEFAULT_VOLT_OFFSET 1.346 // default voltage offset between speed and temp pins from ModernDevice rev p wind sensor
  25. const AP_Param::GroupInfo AP_WindVane::var_info[] = {
  26. // @Param: TYPE
  27. // @DisplayName: Wind Vane Type
  28. // @Description: Wind Vane type
  29. // @Values: 0:None,1:Heading when armed,2:RC input offset heading when armed,3:Analog,4:NMEA,10:SITL
  30. // @User: Standard
  31. // @RebootRequired: True
  32. AP_GROUPINFO_FLAGS("TYPE", 1, AP_WindVane, _direction_type, 0, AP_PARAM_FLAG_ENABLE),
  33. // @Param: RC_IN_NO
  34. // @DisplayName: Wind vane sensor RC Input Channel
  35. // @Description: RC Input Channel to use as wind angle value
  36. // @Range: 0 16
  37. // @Increment: 1
  38. // @User: Standard
  39. AP_GROUPINFO("RC_IN_NO", 2, AP_WindVane, _rc_in_no, 0),
  40. // @Param: DIR_PIN
  41. // @DisplayName: Wind vane analog voltage pin for direction
  42. // @Description: Analog input pin to read as wind vane direction
  43. // @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
  44. // @User: Standard
  45. AP_GROUPINFO("DIR_PIN", 3, AP_WindVane, _dir_analog_pin, WINDVANE_DEFAULT_PIN),
  46. // @Param: DIR_V_MIN
  47. // @DisplayName: Wind vane voltage minimum
  48. // @Description: Minimum voltage supplied by analog wind vane
  49. // @Units: V
  50. // @Increment: 0.01
  51. // @Range: 0 5.0
  52. // @User: Standard
  53. AP_GROUPINFO("DIR_V_MIN", 4, AP_WindVane, _dir_analog_volt_min, 0.0f),
  54. // @Param: DIR_V_MAX
  55. // @DisplayName: Wind vane voltage maximum
  56. // @Description: Maximum voltage supplied by analog wind vane
  57. // @Units: V
  58. // @Increment: 0.01
  59. // @Range: 0 5.0
  60. // @User: Standard
  61. AP_GROUPINFO("DIR_V_MAX", 5, AP_WindVane, _dir_analog_volt_max, 3.3f),
  62. // @Param: DIR_OFS
  63. // @DisplayName: Wind vane headwind offset
  64. // @Description: Angle offset when analog windvane is indicating a headwind, ie 0 degress relative to vehicle
  65. // @Units: deg
  66. // @Increment: 1
  67. // @Range: 0 360
  68. // @User: Standard
  69. AP_GROUPINFO("DIR_OFS", 6, AP_WindVane, _dir_analog_bearing_offset, 0.0f),
  70. // @Param: DIR_FILT
  71. // @DisplayName: Wind vane direction low pass filter frequency
  72. // @Description: Wind vane direction low pass filter frequency, a value of -1 disables filter
  73. // @Units: Hz
  74. // @User: Standard
  75. AP_GROUPINFO("DIR_FILT", 7, AP_WindVane, _dir_filt_hz, 0.5f),
  76. // @Param: CAL
  77. // @DisplayName: Wind vane calibration start
  78. // @Description: Start wind vane calibration by setting this to 1 or 2
  79. // @Values: 0:None, 1:Calibrate direction, 2:Calibrate speed
  80. // @User: Standard
  81. AP_GROUPINFO("CAL", 8, AP_WindVane, _calibration, 0),
  82. // @Param: DIR_DZ
  83. // @DisplayName: Wind vane deadzone when using analog sensor
  84. // @Description: Wind vane deadzone when using analog sensor
  85. // @Units: deg
  86. // @Increment: 1
  87. // @Range: 0 360
  88. // @User: Standard
  89. AP_GROUPINFO("DIR_DZ", 9, AP_WindVane, _dir_analog_deadzone, 0),
  90. // @Param: SPEED_MIN
  91. // @DisplayName: Wind vane cut off wind speed
  92. // @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
  93. // @Units: m/s
  94. // @Increment: 0.1
  95. // @Range: 0 5
  96. // @User: Standard
  97. AP_GROUPINFO("SPEED_MIN", 10, AP_WindVane, _dir_speed_cutoff, 0),
  98. // @Param: SPEED_TYPE
  99. // @DisplayName: Wind speed sensor Type
  100. // @Description: Wind speed sensor type
  101. // @Values: 0:None,1:Airspeed library,2:Modern Devices Wind Sensor,3:RPM library,4:NMEA,10:SITL
  102. // @User: Standard
  103. // @RebootRequired: True
  104. AP_GROUPINFO("SPEED_TYPE", 11, AP_WindVane, _speed_sensor_type, 0),
  105. // @Param: SPEED_PIN
  106. // @DisplayName: Wind vane speed sensor analog pin
  107. // @Description: Wind speed analog speed input pin for Modern Devices Wind Sensor rev. p
  108. // @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
  109. // @User: Standard
  110. AP_GROUPINFO("SPEED_PIN", 12, AP_WindVane, _speed_sensor_speed_pin, WINDSPEED_DEFAULT_SPEED_PIN),
  111. // @Param: TEMP_PIN
  112. // @DisplayName: Wind vane speed sensor analog temp pin
  113. // @Description: Wind speed sensor analog temp input pin for Modern Devices Wind Sensor rev. p, set to -1 to diasble temp readings
  114. // @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
  115. // @User: Standard
  116. AP_GROUPINFO("TEMP_PIN", 13, AP_WindVane, _speed_sensor_temp_pin, WINDSPEED_DEFAULT_TEMP_PIN),
  117. // @Param: SPEED_OFS
  118. // @DisplayName: Wind speed sensor analog voltage offset
  119. // @Description: Wind sensor analog voltage offset at zero wind speed
  120. // @Units: V
  121. // @Increment: 0.01
  122. // @Range: 0 3.3
  123. // @User: Standard
  124. AP_GROUPINFO("SPEED_OFS", 14, AP_WindVane, _speed_sensor_voltage_offset, WINDSPEED_DEFAULT_VOLT_OFFSET),
  125. // @Param: SPEED_FILT
  126. // @DisplayName: Wind speed low pass filter frequency
  127. // @Description: Wind speed low pass filter frequency, a value of -1 disables filter
  128. // @Units: Hz
  129. // @User: Standard
  130. AP_GROUPINFO("SPEED_FILT", 15, AP_WindVane, _speed_filt_hz, 0.5f),
  131. AP_GROUPEND
  132. };
  133. // constructor
  134. AP_WindVane::AP_WindVane()
  135. {
  136. AP_Param::setup_object_defaults(this, var_info);
  137. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  138. if (_singleton) {
  139. AP_HAL::panic("Too many Wind Vane sensors");
  140. }
  141. #endif
  142. _singleton = this;
  143. }
  144. /*
  145. * Get the AP_WindVane singleton
  146. */
  147. AP_WindVane *AP_WindVane::get_singleton()
  148. {
  149. return _singleton;
  150. }
  151. // return true if wind vane is enabled
  152. bool AP_WindVane::enabled() const
  153. {
  154. return _direction_type != WINDVANE_NONE;
  155. }
  156. // return true if wind speed is enabled
  157. bool AP_WindVane::wind_speed_enabled() const
  158. {
  159. return (_speed_sensor_type != WINDSPEED_NONE);
  160. }
  161. // Initialize the Wind Vane object and prepare it for use
  162. void AP_WindVane::init(const AP_SerialManager& serial_manager)
  163. {
  164. // don't construct twice
  165. if (_direction_driver != nullptr || _speed_driver != nullptr ) {
  166. return;
  167. }
  168. // wind direction
  169. switch (_direction_type) {
  170. case WindVaneType::WINDVANE_NONE:
  171. // WindVane disabled
  172. return;
  173. case WindVaneType::WINDVANE_HOME_HEADING:
  174. case WindVaneType::WINDVANE_PWM_PIN:
  175. _direction_driver = new AP_WindVane_Home(*this);
  176. break;
  177. case WindVaneType::WINDVANE_ANALOG_PIN:
  178. _direction_driver = new AP_WindVane_Analog(*this);
  179. break;
  180. case WindVaneType::WINDVANE_SITL:
  181. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  182. _direction_driver = new AP_WindVane_SITL(*this);
  183. #endif
  184. break;
  185. case WindVaneType::WINDVANE_NMEA:
  186. _direction_driver = new AP_WindVane_NMEA(*this);
  187. _direction_driver->init(serial_manager);
  188. break;
  189. }
  190. // wind speed
  191. switch (_speed_sensor_type) {
  192. case Speed_type::WINDSPEED_NONE:
  193. break;
  194. case Speed_type::WINDSPEED_AIRSPEED:
  195. _speed_driver = new AP_WindVane_Airspeed(*this);
  196. break;
  197. case Speed_type::WINDVANE_WIND_SENSOR_REV_P:
  198. _speed_driver = new AP_WindVane_ModernDevice(*this);
  199. break;
  200. case Speed_type::WINDSPEED_SITL:
  201. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  202. // single driver does both speed and direction
  203. if (_direction_type != WindVaneType::WINDVANE_SITL) {
  204. _speed_driver = new AP_WindVane_SITL(*this);
  205. } else {
  206. _speed_driver = _direction_driver;
  207. }
  208. #endif
  209. break;
  210. case Speed_type::WINDSPEED_NMEA:
  211. // single driver does both speed and direction
  212. if (_direction_type != WindVaneType::WINDVANE_NMEA) {
  213. _speed_driver = new AP_WindVane_NMEA(*this);
  214. _speed_driver->init(serial_manager);
  215. } else {
  216. _speed_driver = _direction_driver;
  217. }
  218. break;
  219. case Speed_type::WINDSPEED_RPM:
  220. _speed_driver = new AP_WindVane_RPM(*this);
  221. break;
  222. }
  223. }
  224. // update wind vane, expected to be called at 20hz
  225. void AP_WindVane::update()
  226. {
  227. bool have_speed = _speed_driver != nullptr;
  228. bool have_direciton = _direction_driver != nullptr;
  229. // exit immediately if not enabled
  230. if (!enabled() || (!have_speed && !have_direciton)) {
  231. return;
  232. }
  233. // calibrate if booted and disarmed
  234. if (!hal.util->get_soft_armed()) {
  235. if (_calibration == 1 && have_direciton) {
  236. _direction_driver->calibrate();
  237. } else if (_calibration == 2 && have_speed) {
  238. _speed_driver->calibrate();
  239. } else if (_calibration != 0) {
  240. gcs().send_text(MAV_SEVERITY_INFO, "WindVane: driver not found");
  241. _calibration.set_and_save(0);
  242. }
  243. } else if (_calibration != 0) {
  244. gcs().send_text(MAV_SEVERITY_INFO, "WindVane: disarm for cal");
  245. _calibration.set_and_save(0);
  246. }
  247. // read apparent wind speed
  248. if (have_speed) {
  249. _speed_driver->update_speed();
  250. }
  251. // read apparent wind direction
  252. if (_speed_apparent >= _dir_speed_cutoff && have_direciton) {
  253. // only update if enough wind to move vane
  254. _direction_driver->update_direction();
  255. }
  256. // calculate true wind speed and direction from apparent wind
  257. if (have_speed && have_direciton) {
  258. update_true_wind_speed_and_direction();
  259. } else {
  260. // no wind speed sensor, so can't do true wind calcs
  261. _direction_true = _direction_apparent_ef;
  262. _speed_true = 0.0f;
  263. return;
  264. }
  265. }
  266. // to start direction calibration from mavlink or other
  267. bool AP_WindVane::start_direction_calibration()
  268. {
  269. if (enabled() && (_calibration == 0)) {
  270. _calibration = 1;
  271. return true;
  272. }
  273. return false;
  274. }
  275. // to start speed calibration from mavlink or other
  276. bool AP_WindVane::start_speed_calibration()
  277. {
  278. if (enabled() && (_calibration == 0)) {
  279. _calibration = 2;
  280. return true;
  281. }
  282. return false;
  283. }
  284. // send mavlink wind message
  285. void AP_WindVane::send_wind(mavlink_channel_t chan)
  286. {
  287. // exit immediately if not enabled
  288. if (!enabled()) {
  289. return;
  290. }
  291. // send wind
  292. mavlink_msg_wind_send(
  293. chan,
  294. wrap_360(degrees(get_true_wind_direction_rad())),
  295. get_true_wind_speed(),
  296. 0);
  297. }
  298. // calculate true wind speed and direction from apparent wind
  299. // https://en.wikipedia.org/wiki/Apparent_wind
  300. void AP_WindVane::update_true_wind_speed_and_direction()
  301. {
  302. // if no vehicle speed, can't do calcs
  303. Vector3f veh_velocity;
  304. if (!AP::ahrs().get_velocity_NED(veh_velocity)) {
  305. // if no vehicle speed use apparent speed and direction directly
  306. _direction_true = _direction_apparent_ef;
  307. _speed_true = _speed_apparent;
  308. return;
  309. }
  310. // convert apparent wind speed and direction to 2D vector in same frame as vehicle velocity
  311. const float wind_dir_180 = wrap_PI(_direction_apparent_ef + radians(180));
  312. const Vector2f wind_apparent_vec(cosf(wind_dir_180) * _speed_apparent, sinf(wind_dir_180) * _speed_apparent);
  313. // add vehicle velocity
  314. Vector2f wind_true_vec = Vector2f(wind_apparent_vec.x + veh_velocity.x, wind_apparent_vec.y + veh_velocity.y);
  315. // calculate true speed and direction
  316. _direction_true = wrap_PI(atan2f(wind_true_vec.y, wind_true_vec.x) - radians(180));
  317. _speed_true = wind_true_vec.length();
  318. }
  319. AP_WindVane *AP_WindVane::_singleton = nullptr;
  320. namespace AP {
  321. AP_WindVane *windvane()
  322. {
  323. return AP_WindVane::get_singleton();
  324. }
  325. };