AP_OpticalFlow: use max() macro

This commit is contained in:
Andrew Tridgell 2012-12-08 15:20:20 +11:00
parent 6ee32ea872
commit 7d70ff409d

View File

@ -99,7 +99,7 @@ void AP_OpticalFlow::update_position(float roll, float pitch,
// over 45 degrees // over 45 degrees
if( surface_quality >= 10 && fabs(roll) <= FORTYFIVE_DEGREES if( surface_quality >= 10 && fabs(roll) <= FORTYFIVE_DEGREES
&& fabs(pitch) <= 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 // calculate expected x,y diff due to roll and pitch change
exp_change_x = diff_roll * radians_to_pixels; exp_change_x = diff_roll * radians_to_pixels;
exp_change_y = -diff_pitch * radians_to_pixels; exp_change_y = -diff_pitch * radians_to_pixels;