AP_Vehicle: Change division to multiplication

This commit is contained in:
muramura 2024-04-20 19:21:37 +09:00 committed by Peter Barker
parent b85ecb9526
commit 2cfa6afd87

View File

@ -802,7 +802,7 @@ void AP_Vehicle::update_throttle_notch(AP_InertialSensor::HarmonicNotch &notch)
} else
#else // APM_BUILD_Rover
const AP_MotorsUGV *motors = AP::motors_ugv();
const float motors_throttle = motors != nullptr ? abs(motors->get_throttle() / 100.0f) : 0;
const float motors_throttle = motors != nullptr ? abs(motors->get_throttle() * 0.01f) : 0;
#endif
{
float throttle_freq = ref_freq * sqrtf(MAX(0,motors_throttle) / ref);