From bf738b03a69c4ca42017daf63c5e4bdfac74ce49 Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 12 Mar 2022 02:39:48 +0900 Subject: [PATCH] AP_WheelEncoder: Change from division to multiplication --- libraries/AP_WheelEncoder/AP_WheelRateControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index fe2fce2335..732a2e35c2 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -203,7 +203,7 @@ float AP_WheelRateControl::get_rate_controlled_throttle(uint8_t instance, float _last_update_ms = now; // convert desired rate as a percentage to radians/sec - float desired_rate = desired_rate_pct / 100.0f * get_rate_max_rads(); + float desired_rate = desired_rate_pct * 0.01f * get_rate_max_rads(); // get actual rate from wheeel encoder float actual_rate = _wheel_encoder.get_rate(instance);