diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index 886de7b4c7..861217e0fd 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -182,9 +182,6 @@ void Blimp::ten_hz_logging_loop() if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_EKF_POS(); } - if (should_log(MASK_LOG_MOTBATT)) { - Log_Write_MotBatt(); - } if (should_log(MASK_LOG_RCIN)) { logger.Write_RCIN(); if (rssi.enabled()) { diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index cab5e45a06..bc340974d0 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -361,7 +361,6 @@ private: void Log_Write_Attitude(); void Log_Write_PIDs(); void Log_Write_EKF_POS(); - void Log_Write_MotBatt(); void Log_Write_Data(LogDataID id, int32_t value); void Log_Write_Data(LogDataID id, uint32_t value); void Log_Write_Data(LogDataID id, int16_t value); diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index 0e21817e2a..0eb0b1e6de 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -106,21 +106,6 @@ void Blimp::Log_Write_EKF_POS() ahrs.Write_POS(); } -struct PACKED log_MotBatt { - LOG_PACKET_HEADER; - uint64_t time_us; - float lift_max; - float bat_volt; - float bat_res; - float th_limit; -}; - -// Write an rate packet -void Blimp::Log_Write_MotBatt() -{ - -} - struct PACKED log_Data_Int16t { LOG_PACKET_HEADER; uint64_t time_us; @@ -458,18 +443,6 @@ const struct LogStructure Blimp::log_structure[] = { "CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" }, - // @LoggerMessage: MOTB - // @Description: Battery information - // @Field: TimeUS: Time since system startup - // @Field: LiftMax: Maximum motor compensation gain - // @Field: BatVolt: Ratio betwen detected battery voltage and maximum battery voltage - // @Field: BatRes: Estimated battery resistance - // @Field: ThLimit: Throttle limit set due to battery current limitations - - { - LOG_MOTBATT_MSG, sizeof(log_MotBatt), - "MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" - }, { LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t), "D16", "QBh", "TimeUS,Id,Value", "s--", "F--" @@ -547,7 +520,6 @@ void Blimp::Log_Write_Performance() {} void Blimp::Log_Write_Attitude(void) {} void Blimp::Log_Write_PIDs(void) {} void Blimp::Log_Write_EKF_POS() {} -void Blimp::Log_Write_MotBatt() {} void Blimp::Log_Write_Data(LogDataID id, int32_t value) {} void Blimp::Log_Write_Data(LogDataID id, uint32_t value) {} void Blimp::Log_Write_Data(LogDataID id, int16_t value) {} diff --git a/Blimp/defines.h b/Blimp/defines.h index 6761170847..113f8f9be8 100644 --- a/Blimp/defines.h +++ b/Blimp/defines.h @@ -132,7 +132,6 @@ enum LoggingParameters { LOG_DATA_INT32_MSG, LOG_DATA_UINT32_MSG, LOG_DATA_FLOAT_MSG, - LOG_MOTBATT_MSG, LOG_PARAMTUNE_MSG, LOG_HELI_MSG, LOG_GUIDEDTARGET_MSG,