AP_InertialSensor: correct access beyond array in Ins TCal

This commit is contained in:
Peter Barker 2023-03-28 09:58:56 +11:00 committed by Andrew Tridgell
parent a079b570d5
commit 25c04c1fa2

View File

@ -723,7 +723,7 @@ public:
// instance number for logging // instance number for logging
#if INS_AUX_INSTANCES #if INS_AUX_INSTANCES
uint8_t tcal_instance(const AP_InertialSensor_TCal &tc) const { uint8_t tcal_instance(const AP_InertialSensor_TCal &tc) const {
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) { for (uint8_t i=0; i<INS_MAX_INSTANCES - INS_AUX_INSTANCES; i++) {
if (&tc == &tcal_old_param[i]) { if (&tc == &tcal_old_param[i]) {
return i; return i;
} }