Browse Source

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.
master
Phillip Kocmoud 6 years ago committed by Andrew Tridgell
parent
commit
1dc57c84c4
  1. 5
      Tools/AP_Periph/can.cpp

5
Tools/AP_Periph/can.cpp

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

Loading…
Cancel
Save