POSIX: Workaround for broken px4_read interface to accel

This commit is contained in:
Lorenz Meier 2015-07-01 19:54:17 -07:00
parent ce439345c5
commit b0a0e60c5f

View File

@ -154,6 +154,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
goto out;
}
#ifdef __PX4_NUTTX
if (dynamic) {
/* check measurement result range */
struct accel_report acc;
@ -176,6 +177,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
goto out;
}
}
#endif
out:
px4_close(fd);