ArduCopter: Remove i2c lockup count

This was returned only for a single bus and on all supported platforms
this is hardcoded to 0.
This commit is contained in:
Lucas De Marchi 2016-07-22 14:36:26 -03:00
parent 3223a1a542
commit c0b49f6aeb
2 changed files with 2 additions and 2 deletions

View File

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

View File

@ -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(),
};