AP_OpticalFlow: Change division to multiplication

This commit is contained in:
murata 2022-01-29 12:37:35 +09:00 committed by Peter Barker
parent 9c91e3c793
commit 42d1fd984c
1 changed files with 2 additions and 2 deletions

View File

@ -189,8 +189,8 @@ void OpticalFlow::update(void)
if (_calibrator->update()) {
// apply new calibration values
const Vector2f new_scaling = _calibrator->get_scalars();
const float flow_scalerx_as_multiplier = (1.0 + (_flowScalerX / 1000.0)) * new_scaling.x;
const float flow_scalery_as_multiplier = (1.0 + (_flowScalerY / 1000.0)) * new_scaling.y;
const float flow_scalerx_as_multiplier = (1.0 + (_flowScalerX * 0.001)) * new_scaling.x;
const float flow_scalery_as_multiplier = (1.0 + (_flowScalerY * 0.001)) * new_scaling.y;
_flowScalerX.set_and_save_ifchanged((flow_scalerx_as_multiplier - 1.0) * 1000.0);
_flowScalerY.set_and_save_ifchanged((flow_scalery_as_multiplier - 1.0) * 1000.0);
_flowScalerX.notify();