Browse Source

AP_Camera: Change from labs to abs for floats

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
master
Patrick José Pereira 7 years ago committed by Francisco Ferreira
parent
commit
87c09f98cc
  1. 2
      libraries/AP_Camera/AP_Camera.cpp

2
libraries/AP_Camera/AP_Camera.cpp

@ -287,7 +287,7 @@ void AP_Camera::update() @@ -287,7 +287,7 @@ void AP_Camera::update()
return;
}
if (_max_roll > 0 && labs(ahrs.roll_sensor*1e-2f) > _max_roll) {
if (_max_roll > 0 && fabsf(ahrs.roll_sensor*1e-2f) > _max_roll) {
return;
}

Loading…
Cancel
Save