diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 924e89a827..651e4c6f5a 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -337,7 +337,7 @@ void NOINLINE Copter::send_hwstatus(mavlink_channel_t chan) mavlink_msg_hwstatus_send( chan, hal.analogin->board_voltage()*1000, - hal.i2c->lockup_count()); + 0); } void NOINLINE Copter::send_servo_out(mavlink_channel_t chan) diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 5c70f6ca62..359f5f3812 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -363,7 +363,7 @@ void Copter::Log_Write_Performance() num_loops : perf_info_get_num_loops(), max_time : perf_info_get_max_time(), pm_test : pmTest1, - i2c_lockup_count : hal.i2c->lockup_count(), + i2c_lockup_count : 0, ins_error_count : ins.error_count(), log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(), };