AP_Vehicle: Change division to multiplication
This commit is contained in:
parent
b85ecb9526
commit
2cfa6afd87
@ -802,7 +802,7 @@ void AP_Vehicle::update_throttle_notch(AP_InertialSensor::HarmonicNotch ¬ch)
|
|||||||
} else
|
} else
|
||||||
#else // APM_BUILD_Rover
|
#else // APM_BUILD_Rover
|
||||||
const AP_MotorsUGV *motors = AP::motors_ugv();
|
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
|
#endif
|
||||||
{
|
{
|
||||||
float throttle_freq = ref_freq * sqrtf(MAX(0,motors_throttle) / ref);
|
float throttle_freq = ref_freq * sqrtf(MAX(0,motors_throttle) / ref);
|
||||||
|
Loading…
Reference in New Issue
Block a user