APMrover2: 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:
parent
d854b55b9f
commit
3223a1a542
@ -284,7 +284,7 @@ void Rover::send_hwstatus(mavlink_channel_t chan)
|
|||||||
mavlink_msg_hwstatus_send(
|
mavlink_msg_hwstatus_send(
|
||||||
chan,
|
chan,
|
||||||
hal.analogin->board_voltage()*1000,
|
hal.analogin->board_voltage()*1000,
|
||||||
hal.i2c->lockup_count());
|
0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::send_rangefinder(mavlink_channel_t chan)
|
void Rover::send_rangefinder(mavlink_channel_t chan)
|
||||||
|
@ -180,7 +180,7 @@ void Rover::Log_Write_Performance()
|
|||||||
gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000),
|
gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000),
|
||||||
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
|
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
|
||||||
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 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()
|
ins_error_count : ins.error_count()
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
Loading…
Reference in New Issue
Block a user