AP_Airspeed: add AP_AIRSPEED_ENABLED

This commit is contained in:
Joshua Henderson 2022-01-03 16:16:22 -05:00 committed by Andrew Tridgell
parent 6dc5a9fc54
commit 3cfbad0f4d
3 changed files with 18 additions and 6 deletions

View File

@ -273,7 +273,8 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
#endif // AIRSPEED_MAX_SENSORS
// Note that 21, 22 and 23 are used above by the _OPTIONS, _WIND_MAX and _WIND_WARN parameters. Do not use them!!
// NOTE: Index 63 is used by AIRSPEED_TYPE, Do not use it!: AP_Param converts an index of 0 to 63 so that the index may be bit shifted
AP_GROUPEND
};
@ -597,7 +598,7 @@ void AP_Airspeed::read(uint8_t i)
}
// read all airspeed sensors
void AP_Airspeed::update(bool log)
void AP_Airspeed::update()
{
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
read(i);
@ -624,8 +625,8 @@ void AP_Airspeed::update(bool log)
check_sensor_failures();
#ifndef HAL_BUILD_AP_PERIPH
if (log) {
#if HAL_LOGGING_ENABLED
if (_log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) {
Log_Airspeed();
}
#endif

View File

@ -7,6 +7,11 @@
#include <AP_Math/AP_Math.h>
#include <AP_MSP/msp.h>
#ifndef AP_AIRSPEED_ENABLED
#define AP_AIRSPEED_ENABLED 1
#endif
class AP_Airspeed_Backend;
#ifndef AIRSPEED_MAX_SENSORS
@ -52,13 +57,16 @@ public:
void init(void);
// indicate which bit in LOG_BITMASK indicates we should log airspeed readings
void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }
#if AP_AIRSPEED_AUTOCAL_ENABLE
// inflight ratio calibration
void set_calibration_enabled(bool enable) {calibration_enabled = enable;}
#endif //AP_AIRSPEED_AUTOCAL_ENABLE
// read the analog source and update airspeed
void update(bool log);
void update(void);
// calibrate the airspeed. This must be called on startup if the
// altitude/climb_rate/acceleration interfaces are ever used
@ -251,6 +259,8 @@ private:
uint8_t primary;
uint8_t num_sensors;
uint32_t _log_bit = -1; // stores which bit in LOG_BITMASK is used to indicate we should log airspeed readings
void read(uint8_t i);
// return the differential pressure in Pascal for the last airspeed reading for the requested instance
// returns 0 if the sensor is not enabled

View File

@ -65,6 +65,7 @@ void setup()
board_config.init();
// initialize airspeed
// Note airspeed.set_log_bit(LOG_BIT) would need to be called in order to enable logging
airspeed.init();
airspeed.calibrate(false);
@ -80,7 +81,7 @@ void loop(void)
// current system time in milliseconds
timer = AP_HAL::millis();
airspeed.update(false);
airspeed.update();
airspeed.get_temperature(temperature);
// print temperature and airspeed to console