Skip to content
Snippets Groups Projects
Commit 455b0dca authored by Mark Charlebois's avatar Mark Charlebois
Browse files

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: default avatarMark Charlebois <charlebm@gmail.com>
parent 94b62299
No related branches found
No related tags found
No related merge requests found
......@@ -40,7 +40,7 @@
* @author Johan Jansen <jnsn.johan@gmail.com>
*/
#include <nuttx/config.h>
#include <px4_config.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
......@@ -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
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment