Browse Source

MAVLink app: Fix for hardware multiplier resetting to 1 once limitation was overcome.

sbg
Lorenz Meier 10 years ago
parent
commit
e829eb0670
  1. 3
      src/modules/mavlink/mavlink_main.cpp

3
src/modules/mavlink/mavlink_main.cpp

@ -1282,6 +1282,9 @@ Mavlink::update_rate_mult() @@ -1282,6 +1282,9 @@ Mavlink::update_rate_mult()
/* limit to a max multiplier of 1 */
hardware_mult = fminf(1.0f, hardware_mult);
}
} else {
/* no limitation, set hardware to 1 */
hardware_mult = 1.0f;
}
_last_hw_rate_timestamp = tstatus.timestamp;

Loading…
Cancel
Save