123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147 |
- #pragma once
- #include <AP_Param/AP_Param.h>
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_SerialManager/AP_SerialManager.h>
- class AP_WindVane_Backend;
- class AP_WindVane
- {
- 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;
- friend class AP_WindVane_NMEA;
- public:
- AP_WindVane();
-
- AP_WindVane(const AP_WindVane &other) = delete;
- AP_WindVane &operator=(const AP_WindVane&) = delete;
- static AP_WindVane *get_singleton();
-
- bool enabled() const;
-
- bool wind_speed_enabled() const;
-
- void init(const AP_SerialManager& serial_manager);
-
- void update();
-
- float get_apparent_wind_direction_rad() const {
- return wrap_PI(_direction_apparent_ef - AP::ahrs().yaw);
- }
-
- float get_true_wind_direction_rad() const { return _direction_true; }
-
- float get_apparent_wind_speed() const { return _speed_apparent; }
-
- float get_true_wind_speed() const { return _speed_true; }
-
- void record_home_heading() { _home_heading = AP::ahrs().yaw; }
-
- bool start_direction_calibration();
- bool start_speed_calibration();
-
- void send_wind(mavlink_channel_t chan);
-
- static const struct AP_Param::GroupInfo var_info[];
- private:
-
- AP_Int8 _direction_type;
- AP_Int8 _rc_in_no;
- AP_Int8 _dir_analog_pin;
- AP_Float _dir_analog_volt_min;
- AP_Float _dir_analog_volt_max;
- AP_Float _dir_analog_bearing_offset;
- AP_Float _dir_analog_deadzone;
- AP_Float _dir_filt_hz;
- AP_Int8 _calibration;
- AP_Float _dir_speed_cutoff;
- AP_Int8 _speed_sensor_type;
- AP_Int8 _speed_sensor_speed_pin;
- AP_Float _speed_sensor_temp_pin;
- AP_Float _speed_sensor_voltage_offset;
- AP_Float _speed_filt_hz;
- AP_WindVane_Backend *_direction_driver;
- AP_WindVane_Backend *_speed_driver;
-
- void update_apparent_wind_speed();
-
- void update_apparent_wind_direction();
-
- void update_true_wind_speed_and_direction();
-
- float _direction_apparent_ef;
- float _direction_true;
-
- float _speed_apparent;
- float _speed_true;
-
- float _home_heading;
- enum WindVaneType {
- WINDVANE_NONE = 0,
- WINDVANE_HOME_HEADING = 1,
- WINDVANE_PWM_PIN = 2,
- WINDVANE_ANALOG_PIN = 3,
- WINDVANE_NMEA = 4,
- WINDVANE_SITL = 10
- };
- enum Speed_type {
- WINDSPEED_NONE = 0,
- WINDSPEED_AIRSPEED = 1,
- WINDVANE_WIND_SENSOR_REV_P = 2,
- WINDSPEED_RPM = 3,
- WINDSPEED_NMEA = 4,
- WINDSPEED_SITL = 10
- };
- static AP_WindVane *_singleton;
- };
- namespace AP {
- AP_WindVane *windvane();
- };
|