diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 9115c3a79b..2a5196c367 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -425,6 +425,7 @@ struct PACKED log_MotBatt { // 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 : hal.scheduler->micros64(), @@ -434,6 +435,7 @@ void Copter::Log_Write_MotBatt() th_limit : (float)(motors.get_throttle_limit()) }; DataFlash.WriteBlock(&pkt_mot, sizeof(pkt_mot)); +#endif } struct PACKED log_Startup {