diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index e379eb207d..f012585198 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -253,7 +253,6 @@ public: void Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us=0); void Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc); void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t temperature, uint16_t current_tot); - void Write_Airspeed(); void Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets); void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets); void Write_Current(); diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 3e0c54cf49..dc64b27aca 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -8,7 +8,6 @@ #include #include #include -#include #include #include #include @@ -1530,40 +1529,6 @@ void AP_Logger::Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t vo WriteBlock(&pkt, sizeof(pkt)); } -// Write a AIRSPEED packet -void AP_Logger::Write_Airspeed() -{ - AP_Airspeed *airspeed = AP::airspeed(); - if (airspeed == nullptr) { - return; - } - - uint64_t now = AP_HAL::micros64(); - for (uint8_t i=0; ienabled(i)) { - continue; - } - float temperature; - if (!airspeed->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 : airspeed->get_raw_airspeed(i), - diffpressure : airspeed->get_differential_pressure(i), - temperature : (int16_t)(temperature * 100.0f), - rawpressure : airspeed->get_corrected_pressure(i), - offset : airspeed->get_offset(i), - use : airspeed->use(i), - healthy : airspeed->healthy(i), - health_prob : airspeed->get_health_failure_probability(i), - primary : airspeed->get_primary() - }; - WriteBlock(&pkt, sizeof(pkt)); - } -} - // Write a Yaw PID packet void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info) {