Skip to content

Commit

Permalink
AP_Vehicle: Change division to multiplication
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and peterbarker committed Jan 1, 2025
1 parent 7c6520a commit 039cffb
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 039cffb

Please sign in to comment.