From 3223a1a5426149134d40c4ef5d67658a37d48695 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Fri, 22 Jul 2016 14:36:26 -0300 Subject: [PATCH] APMrover2: Remove i2c lockup count This was returned only for a single bus and on all supported platforms this is hardcoded to 0. --- APMrover2/GCS_Mavlink.cpp | 2 +- APMrover2/Log.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index c456996803..7b79351c9e 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -284,7 +284,7 @@ void Rover::send_hwstatus(mavlink_channel_t chan) mavlink_msg_hwstatus_send( chan, hal.analogin->board_voltage()*1000, - hal.i2c->lockup_count()); + 0); } void Rover::send_rangefinder(mavlink_channel_t chan) diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 7b4f868a36..715d5f0866 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -180,7 +180,7 @@ void Rover::Log_Write_Performance() gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000), gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000), gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000), - i2c_lockup_count: hal.i2c->lockup_count(), + i2c_lockup_count: 0, ins_error_count : ins.error_count() }; DataFlash.WriteBlock(&pkt, sizeof(pkt));