mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
DataFlash: remove check for max compass instances
For all supported boards the maximum number of instances is 3.
This commit is contained in:
parent
1a4a26de2b
commit
19b31ccff1
@ -1555,8 +1555,7 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
|
||||
health : (uint8_t)compass.healthy(0)
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
#if COMPASS_MAX_INSTANCES > 1
|
||||
|
||||
if (compass.get_count() > 1) {
|
||||
const Vector3f &mag_field2 = compass.get_field(1);
|
||||
const Vector3f &mag_offsets2 = compass.get_offsets(1);
|
||||
@ -1577,8 +1576,7 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
|
||||
};
|
||||
WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
#endif
|
||||
#if COMPASS_MAX_INSTANCES > 2
|
||||
|
||||
if (compass.get_count() > 2) {
|
||||
const Vector3f &mag_field3 = compass.get_field(2);
|
||||
const Vector3f &mag_offsets3 = compass.get_offsets(2);
|
||||
@ -1599,7 +1597,6 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
|
||||
};
|
||||
WriteBlock(&pkt3, sizeof(pkt3));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// Write a mode packet.
|
||||
|
Loading…
Reference in New Issue
Block a user