mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: Enable SITL when it is selected
This commit is contained in:
parent
dcafaf3ab2
commit
5825ab4dc6
|
@ -209,12 +209,12 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager)
|
|||
case WindVaneType::WINDVANE_ANALOG_PIN:
|
||||
_direction_driver = new AP_WindVane_Analog(*this);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case WindVaneType::WINDVANE_SITL_TRUE:
|
||||
case WindVaneType::WINDVANE_SITL_APPARENT:
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
_direction_driver = new AP_WindVane_SITL(*this);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
case WindVaneType::WINDVANE_NMEA:
|
||||
_direction_driver = new AP_WindVane_NMEA(*this);
|
||||
_direction_driver->init(serial_manager);
|
||||
|
@ -231,17 +231,17 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager)
|
|||
case Speed_type::WINDVANE_WIND_SENSOR_REV_P:
|
||||
_speed_driver = new AP_WindVane_ModernDevice(*this);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case Speed_type::WINDSPEED_SITL_TRUE:
|
||||
case Speed_type::WINDSPEED_SITL_APPARENT:
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
// single driver does both speed and direction
|
||||
if (_direction_type != _speed_sensor_type) {
|
||||
_speed_driver = new AP_WindVane_SITL(*this);
|
||||
} else {
|
||||
_speed_driver = _direction_driver;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
case Speed_type::WINDSPEED_NMEA:
|
||||
// single driver does both speed and direction
|
||||
if (_direction_type != WindVaneType::WINDVANE_NMEA) {
|
||||
|
|
|
@ -166,8 +166,10 @@ private:
|
|||
WINDVANE_PWM_PIN = 2,
|
||||
WINDVANE_ANALOG_PIN = 3,
|
||||
WINDVANE_NMEA = 4,
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
WINDVANE_SITL_TRUE = 10,
|
||||
WINDVANE_SITL_APPARENT = 11,
|
||||
#endif
|
||||
};
|
||||
|
||||
enum Speed_type {
|
||||
|
@ -176,8 +178,10 @@ private:
|
|||
WINDVANE_WIND_SENSOR_REV_P = 2,
|
||||
WINDSPEED_RPM = 3,
|
||||
WINDSPEED_NMEA = 4,
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
WINDSPEED_SITL_TRUE = 10,
|
||||
WINDSPEED_SITL_APPARENT = 11,
|
||||
#endif
|
||||
};
|
||||
|
||||
static AP_WindVane *_singleton;
|
||||
|
|
Loading…
Reference in New Issue