Copter: no MotBatt logging for TradHeli

This commit is contained in:
Randy Mackay 2015-07-15 16:27:45 +09:00
parent 4cacff54b4
commit 1b68d0eead

View File

@ -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 {