Browse Source

Compass: sanity check instance in set_and_save_offsets

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
16d4af8346
  1. 7
      libraries/AP_Compass/Compass.cpp

7
libraries/AP_Compass/Compass.cpp

@ -162,8 +162,11 @@ Compass::init() @@ -162,8 +162,11 @@ Compass::init()
void
Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
{
_offset[i].set(offsets);
save_offsets(i);
// sanity check compass instance provided
if (i < COMPASS_MAX_INSTANCES) {
_offset[i].set(offsets);
save_offsets(i);
}
}
void

Loading…
Cancel
Save