123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371 |
- #include "AP_WindVane.h"
- #include "AP_WindVane_Home.h"
- #include "AP_WindVane_Analog.h"
- #include "AP_WindVane_ModernDevice.h"
- #include "AP_WindVane_Airspeed.h"
- #include "AP_WindVane_RPM.h"
- #include "AP_WindVane_SITL.h"
- #include "AP_WindVane_NMEA.h"
- #define WINDVANE_DEFAULT_PIN 15
- #define WINDSPEED_DEFAULT_SPEED_PIN 14
- #define WINDSPEED_DEFAULT_TEMP_PIN 13
- #define WINDSPEED_DEFAULT_VOLT_OFFSET 1.346
- const AP_Param::GroupInfo AP_WindVane::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO_FLAGS("TYPE", 1, AP_WindVane, _direction_type, 0, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
-
- AP_GROUPINFO("RC_IN_NO", 2, AP_WindVane, _rc_in_no, 0),
-
-
-
-
-
- AP_GROUPINFO("DIR_PIN", 3, AP_WindVane, _dir_analog_pin, WINDVANE_DEFAULT_PIN),
-
-
-
-
-
-
-
- AP_GROUPINFO("DIR_V_MIN", 4, AP_WindVane, _dir_analog_volt_min, 0.0f),
-
-
-
-
-
-
-
- AP_GROUPINFO("DIR_V_MAX", 5, AP_WindVane, _dir_analog_volt_max, 3.3f),
-
-
-
-
-
-
-
- AP_GROUPINFO("DIR_OFS", 6, AP_WindVane, _dir_analog_bearing_offset, 0.0f),
-
-
-
-
-
- AP_GROUPINFO("DIR_FILT", 7, AP_WindVane, _dir_filt_hz, 0.5f),
-
-
-
-
-
- AP_GROUPINFO("CAL", 8, AP_WindVane, _calibration, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("DIR_DZ", 9, AP_WindVane, _dir_analog_deadzone, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("SPEED_MIN", 10, AP_WindVane, _dir_speed_cutoff, 0),
-
-
-
-
-
-
- AP_GROUPINFO("SPEED_TYPE", 11, AP_WindVane, _speed_sensor_type, 0),
-
-
-
-
-
- AP_GROUPINFO("SPEED_PIN", 12, AP_WindVane, _speed_sensor_speed_pin, WINDSPEED_DEFAULT_SPEED_PIN),
-
-
-
-
-
- AP_GROUPINFO("TEMP_PIN", 13, AP_WindVane, _speed_sensor_temp_pin, WINDSPEED_DEFAULT_TEMP_PIN),
-
-
-
-
-
-
-
- AP_GROUPINFO("SPEED_OFS", 14, AP_WindVane, _speed_sensor_voltage_offset, WINDSPEED_DEFAULT_VOLT_OFFSET),
-
-
-
-
-
- AP_GROUPINFO("SPEED_FILT", 15, AP_WindVane, _speed_filt_hz, 0.5f),
- AP_GROUPEND
- };
- AP_WindVane::AP_WindVane()
- {
- AP_Param::setup_object_defaults(this, var_info);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- if (_singleton) {
- AP_HAL::panic("Too many Wind Vane sensors");
- }
- #endif
- _singleton = this;
- }
- AP_WindVane *AP_WindVane::get_singleton()
- {
- return _singleton;
- }
- bool AP_WindVane::enabled() const
- {
- return _direction_type != WINDVANE_NONE;
- }
- bool AP_WindVane::wind_speed_enabled() const
- {
- return (_speed_sensor_type != WINDSPEED_NONE);
- }
- void AP_WindVane::init(const AP_SerialManager& serial_manager)
- {
-
- if (_direction_driver != nullptr || _speed_driver != nullptr ) {
- return;
- }
-
- switch (_direction_type) {
- case WindVaneType::WINDVANE_NONE:
-
- return;
- case WindVaneType::WINDVANE_HOME_HEADING:
- case WindVaneType::WINDVANE_PWM_PIN:
- _direction_driver = new AP_WindVane_Home(*this);
- break;
- case WindVaneType::WINDVANE_ANALOG_PIN:
- _direction_driver = new AP_WindVane_Analog(*this);
- break;
- case WindVaneType::WINDVANE_SITL:
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- _direction_driver = new AP_WindVane_SITL(*this);
- #endif
- break;
- case WindVaneType::WINDVANE_NMEA:
- _direction_driver = new AP_WindVane_NMEA(*this);
- _direction_driver->init(serial_manager);
- break;
- }
-
- switch (_speed_sensor_type) {
- case Speed_type::WINDSPEED_NONE:
- break;
- case Speed_type::WINDSPEED_AIRSPEED:
- _speed_driver = new AP_WindVane_Airspeed(*this);
- break;
- case Speed_type::WINDVANE_WIND_SENSOR_REV_P:
- _speed_driver = new AP_WindVane_ModernDevice(*this);
- break;
- case Speed_type::WINDSPEED_SITL:
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
-
- if (_direction_type != WindVaneType::WINDVANE_SITL) {
- _speed_driver = new AP_WindVane_SITL(*this);
- } else {
- _speed_driver = _direction_driver;
- }
- #endif
- break;
- case Speed_type::WINDSPEED_NMEA:
-
- if (_direction_type != WindVaneType::WINDVANE_NMEA) {
- _speed_driver = new AP_WindVane_NMEA(*this);
- _speed_driver->init(serial_manager);
- } else {
- _speed_driver = _direction_driver;
- }
- break;
- case Speed_type::WINDSPEED_RPM:
- _speed_driver = new AP_WindVane_RPM(*this);
- break;
- }
- }
- void AP_WindVane::update()
- {
- bool have_speed = _speed_driver != nullptr;
- bool have_direciton = _direction_driver != nullptr;
-
- if (!enabled() || (!have_speed && !have_direciton)) {
- return;
- }
-
- if (!hal.util->get_soft_armed()) {
- if (_calibration == 1 && have_direciton) {
- _direction_driver->calibrate();
- } else if (_calibration == 2 && have_speed) {
- _speed_driver->calibrate();
- } else if (_calibration != 0) {
- gcs().send_text(MAV_SEVERITY_INFO, "WindVane: driver not found");
- _calibration.set_and_save(0);
- }
- } else if (_calibration != 0) {
- gcs().send_text(MAV_SEVERITY_INFO, "WindVane: disarm for cal");
- _calibration.set_and_save(0);
- }
-
- if (have_speed) {
- _speed_driver->update_speed();
- }
-
- if (_speed_apparent >= _dir_speed_cutoff && have_direciton) {
-
- _direction_driver->update_direction();
- }
-
- if (have_speed && have_direciton) {
- update_true_wind_speed_and_direction();
- } else {
-
- _direction_true = _direction_apparent_ef;
- _speed_true = 0.0f;
- return;
- }
- }
- bool AP_WindVane::start_direction_calibration()
- {
- if (enabled() && (_calibration == 0)) {
- _calibration = 1;
- return true;
- }
- return false;
- }
- bool AP_WindVane::start_speed_calibration()
- {
- if (enabled() && (_calibration == 0)) {
- _calibration = 2;
- return true;
- }
- return false;
- }
- void AP_WindVane::send_wind(mavlink_channel_t chan)
- {
-
- if (!enabled()) {
- return;
- }
-
- mavlink_msg_wind_send(
- chan,
- wrap_360(degrees(get_true_wind_direction_rad())),
- get_true_wind_speed(),
- 0);
- }
- void AP_WindVane::update_true_wind_speed_and_direction()
- {
-
- Vector3f veh_velocity;
- if (!AP::ahrs().get_velocity_NED(veh_velocity)) {
-
- _direction_true = _direction_apparent_ef;
- _speed_true = _speed_apparent;
- return;
- }
-
- 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);
-
- Vector2f wind_true_vec = Vector2f(wind_apparent_vec.x + veh_velocity.x, wind_apparent_vec.y + veh_velocity.y);
-
- _direction_true = wrap_PI(atan2f(wind_true_vec.y, wind_true_vec.x) - radians(180));
- _speed_true = wind_true_vec.length();
- }
- AP_WindVane *AP_WindVane::_singleton = nullptr;
- namespace AP {
- AP_WindVane *windvane()
- {
- return AP_WindVane::get_singleton();
- }
- };
|