From 455b0dcaff7929f69a382fc07efd94691c6fc794 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Mon, 20 Apr 2015 12:04:46 -0700 Subject: [PATCH] Fixed parenthesis bug Clang found the following: if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) which is doing fsbsf( bool ) Fixed to be: if (fabsf(airspeed.indicated_airspeed_m_s) > 6.0f) Signed-off-by: Mark Charlebois --- src/modules/commander/PreflightCheck.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/PreflightCheck.cpp b/src/modules/commander/PreflightCheck.cpp index 6bb7e5c245..2c05fb33d1 100644 --- a/src/modules/commander/PreflightCheck.cpp +++ b/src/modules/commander/PreflightCheck.cpp @@ -40,7 +40,7 @@ * @author Johan Jansen */ -#include +#include #include #include #include @@ -259,7 +259,7 @@ static bool airspeedCheck(int mavlink_fd, bool optional) goto out; } - if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) { + if (fabsf(airspeed.indicated_airspeed_m_s) > 6.0f) { mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION ISSUE"); // XXX do not make this fatal yet }