mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: add and use AP_WINDVANE_*_ENABLED defines
This commit is contained in:
parent
75217ec1e6
commit
ff86e2dda8
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_ENABLED
|
||||
|
||||
#include "AP_WindVane.h"
|
||||
|
||||
#include "AP_WindVane_Home.h"
|
||||
|
@ -202,36 +206,46 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager)
|
|||
case WindVaneType::WINDVANE_NONE:
|
||||
// WindVane disabled
|
||||
return;
|
||||
#if AP_WINDVANE_HOME_ENABLED
|
||||
case WindVaneType::WINDVANE_HOME_HEADING:
|
||||
case WindVaneType::WINDVANE_PWM_PIN:
|
||||
_direction_driver = new AP_WindVane_Home(*this);
|
||||
break;
|
||||
#endif
|
||||
#if AP_WINDVANE_ANALOG_ENABLED
|
||||
case WindVaneType::WINDVANE_ANALOG_PIN:
|
||||
_direction_driver = new AP_WindVane_Analog(*this);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif
|
||||
#if AP_WINDVANE_SIM_ENABLED
|
||||
case WindVaneType::WINDVANE_SITL_TRUE:
|
||||
case WindVaneType::WINDVANE_SITL_APPARENT:
|
||||
_direction_driver = new AP_WindVane_SITL(*this);
|
||||
break;
|
||||
#endif
|
||||
#if AP_WINDVANE_NMEA_ENABLED
|
||||
case WindVaneType::WINDVANE_NMEA:
|
||||
_direction_driver = new AP_WindVane_NMEA(*this);
|
||||
_direction_driver->init(serial_manager);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
// wind speed
|
||||
switch (_speed_sensor_type) {
|
||||
case Speed_type::WINDSPEED_NONE:
|
||||
break;
|
||||
#if AP_WINDVANE_AIRSPEED_ENABLED
|
||||
case Speed_type::WINDSPEED_AIRSPEED:
|
||||
_speed_driver = new AP_WindVane_Airspeed(*this);
|
||||
break;
|
||||
#endif
|
||||
#if AP_WINDVANE_MODERNDEVICE_ENABLED
|
||||
case Speed_type::WINDVANE_WIND_SENSOR_REV_P:
|
||||
_speed_driver = new AP_WindVane_ModernDevice(*this);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif
|
||||
#if AP_WINDVANE_SIM_ENABLED
|
||||
case Speed_type::WINDSPEED_SITL_TRUE:
|
||||
case Speed_type::WINDSPEED_SITL_APPARENT:
|
||||
// single driver does both speed and direction
|
||||
|
@ -241,7 +255,8 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager)
|
|||
_speed_driver = _direction_driver;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#endif // AP_WINDVANE_SIM_ENABLED
|
||||
#if AP_WINDVANE_NMEA_ENABLED
|
||||
case Speed_type::WINDSPEED_NMEA:
|
||||
// single driver does both speed and direction
|
||||
if (_direction_type != WindVaneType::WINDVANE_NMEA) {
|
||||
|
@ -251,9 +266,12 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager)
|
|||
_speed_driver = _direction_driver;
|
||||
}
|
||||
break;
|
||||
#endif // AP_WINDVANE_NMEA_ENABLED
|
||||
#if AP_WINDVANE_RPM_ENABLED
|
||||
case Speed_type::WINDSPEED_RPM:
|
||||
_speed_driver = new AP_WindVane_RPM(*this);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -476,3 +494,5 @@ namespace AP {
|
|||
return AP_WindVane::get_singleton();
|
||||
}
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_ENABLED
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <Filter/Filter.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
@ -162,11 +166,17 @@ private:
|
|||
|
||||
enum WindVaneType {
|
||||
WINDVANE_NONE = 0,
|
||||
#if AP_WINDVANE_HOME_ENABLED
|
||||
WINDVANE_HOME_HEADING = 1,
|
||||
WINDVANE_PWM_PIN = 2,
|
||||
#endif
|
||||
#if AP_WINDVANE_ANALOG_ENABLED
|
||||
WINDVANE_ANALOG_PIN = 3,
|
||||
#endif
|
||||
#if AP_WINDVANE_NMEA_ENABLED
|
||||
WINDVANE_NMEA = 4,
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif
|
||||
#if AP_WINDVANE_SIM_ENABLED
|
||||
WINDVANE_SITL_TRUE = 10,
|
||||
WINDVANE_SITL_APPARENT = 11,
|
||||
#endif
|
||||
|
@ -174,11 +184,17 @@ private:
|
|||
|
||||
enum Speed_type {
|
||||
WINDSPEED_NONE = 0,
|
||||
#if AP_WINDVANE_AIRSPEED_ENABLED
|
||||
WINDSPEED_AIRSPEED = 1,
|
||||
#endif
|
||||
WINDVANE_WIND_SENSOR_REV_P = 2,
|
||||
#if AP_WINDVANE_RPM_ENABLED
|
||||
WINDSPEED_RPM = 3,
|
||||
#endif
|
||||
#if AP_WINDVANE_NMEA_ENABLED
|
||||
WINDSPEED_NMEA = 4,
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif
|
||||
#if AP_WINDVANE_SIM_ENABLED
|
||||
WINDSPEED_SITL_TRUE = 10,
|
||||
WINDSPEED_SITL_APPARENT = 11,
|
||||
#endif
|
||||
|
@ -190,3 +206,5 @@ private:
|
|||
namespace AP {
|
||||
AP_WindVane *windvane();
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_ENABLED
|
||||
|
|
|
@ -13,14 +13,18 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_AIRSPEED_ENABLED
|
||||
|
||||
#include "AP_WindVane_Airspeed.h"
|
||||
|
||||
void AP_WindVane_Airspeed::update_speed()
|
||||
{
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
const AP_Airspeed* airspeed = AP_Airspeed::get_singleton();
|
||||
if (airspeed != nullptr) {
|
||||
_frontend._speed_apparent_raw = airspeed->get_raw_airspeed();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_AIRSPEED_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_AIRSPEED_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
|
@ -27,3 +31,5 @@ public:
|
|||
// update state
|
||||
void update_speed() override;
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_AIRSPEED_ENABLED
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_ANALOG_ENABLED
|
||||
|
||||
#include "AP_WindVane_Analog.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
@ -82,3 +86,5 @@ void AP_WindVane_Analog::calibrate()
|
|||
_cal_start_ms = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_ANALOG_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_ANALOG_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
class AP_WindVane_Analog : public AP_WindVane_Backend
|
||||
|
@ -35,3 +39,5 @@ private:
|
|||
float _cal_volt_min;
|
||||
float _cal_volt_max;
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_ANALOG_ENABLED
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_ENABLED
|
||||
|
||||
#include "AP_WindVane.h"
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
|
@ -31,3 +35,5 @@ void AP_WindVane_Backend::calibrate()
|
|||
_frontend._calibration.set_and_save(0);
|
||||
return;
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_ENABLED
|
||||
|
||||
#include "AP_WindVane.h"
|
||||
|
||||
class AP_WindVane_Backend
|
||||
|
@ -39,3 +43,5 @@ protected:
|
|||
AP_WindVane &_frontend;
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_ENABLED
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_HOME_ENABLED
|
||||
|
||||
#include "AP_WindVane_Home.h"
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -30,3 +34,5 @@ void AP_WindVane_Home::update_direction()
|
|||
|
||||
_frontend._direction_apparent_raw = wrap_PI(direction_apparent_ef - AP::ahrs().yaw);
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_HOME_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_HOME_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
|
@ -26,3 +30,5 @@ public:
|
|||
// update state
|
||||
void update_direction() override;
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_HOME_ENABLED
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_MODERNDEVICE_ENABLED
|
||||
|
||||
#include "AP_WindVane_ModernDevice.h"
|
||||
// read wind speed from Modern Device rev p wind sensor
|
||||
// https://moderndevice.com/news/calibrating-rev-p-wind-sensor-new-regression/
|
||||
|
@ -70,3 +74,5 @@ void AP_WindVane_ModernDevice::calibrate()
|
|||
_frontend._speed_sensor_voltage_offset.set_and_save(_current_analog_voltage);
|
||||
_frontend._calibration.set_and_save(0);
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_MODERNDEVICE_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_MODERNDEVICE_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
class AP_WindVane_ModernDevice : public AP_WindVane_Backend
|
||||
|
@ -33,3 +37,5 @@ private:
|
|||
AP_HAL::AnalogSource *_speed_analog_source;
|
||||
AP_HAL::AnalogSource *_temp_analog_source;
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_MODERNDEVICE_ENABLED
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_NMEA_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_WindVane_NMEA.h"
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
@ -197,3 +201,5 @@ bool AP_WindVane_NMEA::decode_latest_term()
|
|||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_NMEA_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_NMEA_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
class AP_WindVane_NMEA : public AP_WindVane_Backend
|
||||
|
@ -54,3 +58,5 @@ private:
|
|||
bool _sentence_valid; // is current sentence valid so far
|
||||
bool _sentence_done; // true if this sentence has already been decoded
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_NMEA_ENABLED
|
||||
|
|
|
@ -15,11 +15,14 @@
|
|||
|
||||
#include "AP_WindVane_RPM.h"
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_RPM_ENABLED
|
||||
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
|
||||
void AP_WindVane_RPM::update_speed()
|
||||
{
|
||||
#if AP_RPM_ENABLED
|
||||
const AP_RPM* rpm = AP_RPM::get_singleton();
|
||||
if (rpm != nullptr) {
|
||||
float temp_speed;
|
||||
|
@ -28,5 +31,6 @@ void AP_WindVane_RPM::update_speed()
|
|||
_frontend._speed_apparent_raw = temp_speed;
|
||||
}
|
||||
}
|
||||
#endif // AP_RPM_ENABLED
|
||||
}
|
||||
|
||||
#endif // AP_WINDVANE_RPM_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_RPM_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
class AP_WindVane_RPM : public AP_WindVane_Backend
|
||||
|
@ -25,3 +29,5 @@ public:
|
|||
// update state
|
||||
void update_speed() override;
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_RPM_ENABLED
|
||||
|
|
|
@ -13,9 +13,11 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_WindVane_SITL.h"
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#if AP_WINDVANE_SIM_ENABLED
|
||||
|
||||
#include "AP_WindVane_SITL.h"
|
||||
|
||||
#include <SITL/SITL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -71,4 +73,4 @@ void AP_WindVane_SITL::update_speed()
|
|||
_frontend._speed_apparent_raw = AP::sitl()->get_apparent_wind_spd();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif // AP_WINDVANE_SIM_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_WindVane_config.h"
|
||||
|
||||
#if AP_WINDVANE_SIM_ENABLED
|
||||
|
||||
#include "AP_WindVane_Backend.h"
|
||||
|
||||
class AP_WindVane_SITL : public AP_WindVane_Backend
|
||||
|
@ -29,3 +33,5 @@ public:
|
|||
void update_speed() override;
|
||||
#endif
|
||||
};
|
||||
|
||||
#endif // AP_WINDVANE_SIM_ENABLED
|
||||
|
|
|
@ -0,0 +1,42 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#include <AP_Airspeed/AP_Airspeed_config.h>
|
||||
#include <AP_RPM/AP_RPM_config.h>
|
||||
|
||||
#ifndef AP_WINDVANE_ENABLED
|
||||
#define AP_WINDVANE_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_WINDVANE_BACKEND_DEFAULT_ENABLED AP_WINDVANE_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_AIRSPEED_ENABLED
|
||||
#define AP_WINDVANE_AIRSPEED_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED && AP_AIRSPEED_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_ANALOG_ENABLED
|
||||
#define AP_WINDVANE_ANALOG_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_HOME_ENABLED
|
||||
#define AP_WINDVANE_HOME_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_MODERNDEVICE_ENABLED
|
||||
#define AP_WINDVANE_MODERNDEVICE_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_NMEA_ENABLED
|
||||
#define AP_WINDVANE_NMEA_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_RPM_ENABLED
|
||||
#define AP_WINDVANE_RPM_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED && AP_RPM_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_WINDVANE_SIM_ENABLED
|
||||
#define AP_WINDVANE_SIM_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED
|
||||
#endif
|
Loading…
Reference in New Issue