From 7d70ff409d34aa18862cc371501753c2274feb7f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Dec 2012 15:20:20 +1100 Subject: [PATCH] AP_OpticalFlow: use max() macro --- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index c6f0946d74..4bed2a5480 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -99,7 +99,7 @@ void AP_OpticalFlow::update_position(float roll, float pitch, // over 45 degrees if( surface_quality >= 10 && fabs(roll) <= FORTYFIVE_DEGREES && fabs(pitch) <= FORTYFIVE_DEGREES ) { - altitude = (altitude > 0 ? altitude : 0); + altitude = max(altitude, 0); // calculate expected x,y diff due to roll and pitch change exp_change_x = diff_roll * radians_to_pixels; exp_change_y = -diff_pitch * radians_to_pixels;