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 Randy Mackay
parent aecffd2778
commit f3502a71e9
1 changed files with 1 additions and 1 deletions

View File

@ -723,7 +723,7 @@ public:
// instance number for logging
#if INS_AUX_INSTANCES
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]) {
return i;
}