From d50e4d03f426619728702d1ace59f764f498ca0e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 20 Nov 2020 09:25:51 +1100 Subject: [PATCH] AP_Logger: remove time_us parameter to several sensor logging methods These were used by the old Replay code to try to provide a frame of sensor data by correlating the timestamps. That Replay code has been removed. --- libraries/AP_Logger/AP_Logger.h | 6 +++--- libraries/AP_Logger/LogFile.cpp | 20 +++++++------------- 2 files changed, 10 insertions(+), 16 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index aff5a312f8..07341752a1 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -229,7 +229,7 @@ public: void Write_Event(LogEvent id); void Write_Error(LogErrorSubsystem sub_system, LogErrorCode error_code); - void Write_GPS(uint8_t instance, uint64_t time_us=0); + void Write_GPS(uint8_t instance); void Write_IMU(); bool Write_ISBH(uint16_t seqno, AP_InertialSensor::IMU_SENSOR_TYPE sensor_type, @@ -248,7 +248,7 @@ public: void Write_RCOUT(void); void Write_RSSI(); void Write_Rally(); - void Write_Baro(uint64_t time_us=0); + void Write_Baro(); void Write_Power(void); void Write_AHRS2(); void Write_POS(); @@ -264,7 +264,7 @@ public: void Write_Attitude(const Vector3f &targets); void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets); void Write_Current(); - void Write_Compass(uint64_t time_us=0); + void Write_Compass(); void Write_Mode(uint8_t mode, const ModeReason reason); void Write_EntireMission(); diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 120382f537..11f977c018 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -131,12 +131,10 @@ bool AP_Logger_Backend::Write_Parameter(const AP_Param *ap, } // Write an GPS packet -void AP_Logger::Write_GPS(uint8_t i, uint64_t time_us) +void AP_Logger::Write_GPS(uint8_t i) { const AP_GPS &gps = AP::gps(); - if (time_us == 0) { - time_us = AP_HAL::micros64(); - } + const uint64_t time_us = AP_HAL::micros64(); const struct Location &loc = gps.location(i); float yaw_deg=0, yaw_accuracy_deg=0; @@ -290,11 +288,9 @@ void AP_Logger::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance) } // Write a BARO packet -void AP_Logger::Write_Baro(uint64_t time_us) +void AP_Logger::Write_Baro() { - if (time_us == 0) { - time_us = AP_HAL::micros64(); - } + const uint64_t time_us = AP_HAL::micros64(); const AP_Baro &baro = AP::baro(); for (uint8_t i=0; i< baro.num_instances(); i++) { Write_Baro_instance(time_us, i); @@ -330,7 +326,7 @@ void AP_Logger::Write_IMU_instance(const uint64_t time_us, const uint8_t imu_ins // Write an raw accel/gyro data packet void AP_Logger::Write_IMU() { - uint64_t time_us = AP_HAL::micros64(); + const uint64_t time_us = AP_HAL::micros64(); const AP_InertialSensor &ins = AP::ins(); @@ -692,11 +688,9 @@ void AP_Logger::Write_Compass_instance(const uint64_t time_us, const uint8_t mag } // Write a Compass packet -void AP_Logger::Write_Compass(uint64_t time_us) +void AP_Logger::Write_Compass() { - if (time_us == 0) { - time_us = AP_HAL::micros64(); - } + const uint64_t time_us = AP_HAL::micros64(); const Compass &compass = AP::compass(); for (uint8_t i=0; i