diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index b9de7d75b7..91d5f369ad 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -491,7 +491,7 @@ void Copter::ten_hz_logging_loop() Log_Write_EKF_POS(); } if (should_log(MASK_LOG_MOTBATT)) { - Log_Write_MotBatt(); + motors->Log_Write(); } if (should_log(MASK_LOG_RCIN)) { logger.Write_RCIN(); diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index df355f6e96..02d3881145 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -786,7 +786,6 @@ private: void Log_Write_Control_Tuning(); void Log_Write_Attitude(); 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/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 1b5582dd48..77459a5d7e 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -94,31 +94,6 @@ void Copter::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 Copter::Log_Write_MotBatt() -{ -#if FRAME_CONFIG != HELI_FRAME - struct log_MotBatt pkt_mot = { - LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG), - time_us : AP_HAL::micros64(), - lift_max : (float)(motors->get_lift_max()), - bat_volt : (float)(motors->get_batt_voltage_filt()), - bat_res : (float)(battery.get_resistance()), - th_limit : (float)(motors->get_throttle_limit()) - }; - logger.WriteBlock(&pkt_mot, sizeof(pkt_mot)); -#endif -} - struct PACKED log_Data_Int16t { LOG_PACKET_HEADER; uint64_t time_us; @@ -467,17 +442,6 @@ const struct LogStructure Copter::log_structure[] = { { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), "CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" , true }, - -// @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-" , true }, { LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t), "D16", "QBh", "TimeUS,Id,Value", "s--", "F--" }, { LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t), @@ -572,7 +536,6 @@ void Copter::log_init(void) void Copter::Log_Write_Control_Tuning() {} void Copter::Log_Write_Attitude(void) {} void Copter::Log_Write_EKF_POS() {} -void Copter::Log_Write_MotBatt() {} void Copter::Log_Write_Data(LogDataID id, int32_t value) {} void Copter::Log_Write_Data(LogDataID id, uint32_t value) {} void Copter::Log_Write_Data(LogDataID id, int16_t value) {} diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index fb36ac0c26..cb27f60ab6 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -116,7 +116,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,