mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_InertialSensor: correct access beyond array in Ins TCal
This commit is contained in:
parent
a079b570d5
commit
25c04c1fa2
@ -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;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user