AP_Airspeed: move logging of ARSP into Airspeed library

This commit is contained in:
Peter Barker 2019-04-06 13:48:44 +11:00 committed by Andrew Tridgell
parent d90e554608
commit f0379ff7f0
2 changed files with 50 additions and 19 deletions

View File

@ -457,7 +457,35 @@ void AP_Airspeed::update(bool log)
check_sensor_failures();
if (log) {
AP::logger().Write_Airspeed();
Log_Airspeed();
}
}
void AP_Airspeed::Log_Airspeed()
{
const uint64_t now = AP_HAL::micros64();
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
if (!enabled(i)) {
continue;
}
float temperature;
if (!get_temperature(i, temperature)) {
temperature = 0;
}
struct log_AIRSPEED pkt = {
LOG_PACKET_HEADER_INIT(i==0?LOG_ARSP_MSG:LOG_ASP2_MSG),
time_us : now,
airspeed : get_raw_airspeed(i),
diffpressure : get_differential_pressure(i),
temperature : (int16_t)(temperature * 100.0f),
rawpressure : get_corrected_pressure(i),
offset : get_offset(i),
use : use(i),
healthy : healthy(i),
health_prob : get_health_failure_probability(i),
primary : get_primary()
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
}

View File

@ -101,18 +101,6 @@ public:
}
float get_differential_pressure(void) const { return get_differential_pressure(primary); }
// return the current calibration offset
float get_offset(uint8_t i) const {
return param[i].offset;
}
float get_offset(void) const { return get_offset(primary); }
// return the current corrected pressure
float get_corrected_pressure(uint8_t i) const {
return state[i].corrected_pressure;
}
float get_corrected_pressure(void) const { return get_corrected_pressure(primary); }
// set the apparent to true airspeed ratio
void set_EAS2TAS(uint8_t i, float v) {
state[i].EAS2TAS = v;
@ -125,12 +113,6 @@ public:
}
float get_EAS2TAS(void) const { return get_EAS2TAS(primary); }
// get the failure health probability
float get_health_failure_probability(uint8_t i) const {
return state[i].failures.health_probability;
}
float get_health_failure_probability(void) const { return get_health_failure_probability(primary); }
// update airspeed ratio calibration
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
@ -238,15 +220,36 @@ private:
// return the differential pressure in Pascal for the last airspeed reading for the requested instance
// returns 0 if the sensor is not enabled
float get_pressure(uint8_t i);
// return the current corrected pressure
float get_corrected_pressure(uint8_t i) const {
return state[i].corrected_pressure;
}
float get_corrected_pressure(void) const {
return get_corrected_pressure(primary);
}
// get the failure health probability
float get_health_failure_probability(uint8_t i) const {
return state[i].failures.health_probability;
}
float get_health_failure_probability(void) const {
return get_health_failure_probability(primary);
}
void update_calibration(uint8_t i, float raw_pressure);
void update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
void send_airspeed_calibration(const Vector3f &vg);
// return the current calibration offset
float get_offset(uint8_t i) const {
return param[i].offset;
}
float get_offset(void) const { return get_offset(primary); }
void check_sensor_failures();
void check_sensor_ahrs_wind_max_failures(uint8_t i);
AP_Airspeed_Backend *sensor[AIRSPEED_MAX_SENSORS];
void Log_Airspeed();
};
namespace AP {