AP_Periph : CAN

Remove 100 times message counter to improve magnetometer performance.

Tested and uavcan.equipment.ahrs.MagneticFieldStrength improves from 7msgs/sec to 75msgs/sec which is likely the output rate of the actual sensor.
This commit is contained in:
Phillip Kocmoud 2019-08-28 20:03:39 -05:00 committed by Andrew Tridgell
parent 49b0d46612
commit 1dc57c84c4

View File

@ -693,11 +693,6 @@ void AP_Periph_FW::can_mag_update(void)
if (last_mag_update_ms == compass.last_update_ms()) { if (last_mag_update_ms == compass.last_update_ms()) {
return; return;
} }
static uint8_t counter;
if (counter++ != 100) {
return;
}
counter = 0;
last_mag_update_ms = compass.last_update_ms(); last_mag_update_ms = compass.last_update_ms();
const Vector3f &field = compass.get_field(); const Vector3f &field = compass.get_field();