From 3f7d4de74a5ca206f614b6ec2642409be7ea3493 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Tue, 21 Apr 2015 17:26:07 -0700 Subject: [PATCH] Posix: fixed ioctl calls to be px4_ioctl Signed-off-by: Mark Charlebois --- src/modules/commander/PreflightCheck_posix.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/PreflightCheck_posix.cpp b/src/modules/commander/PreflightCheck_posix.cpp index 1f8791fe33..5567b43529 100644 --- a/src/modules/commander/PreflightCheck_posix.cpp +++ b/src/modules/commander/PreflightCheck_posix.cpp @@ -88,7 +88,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional) int calibration_devid; int ret; - int devid = ioctl(fd, DEVIOCGDEVICEID, 0); + int devid = px4_ioctl(fd, DEVIOCGDEVICEID, 0); sprintf(s, "CAL_MAG%u_ID", instance); param_get(param_find(s), &(calibration_devid)); @@ -132,7 +132,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional, int calibration_devid; int ret; - int devid = ioctl(fd, DEVIOCGDEVICEID, 0); + int devid = px4_ioctl(fd, DEVIOCGDEVICEID, 0); sprintf(s, "CAL_ACC%u_ID", instance); param_get(param_find(s), &(calibration_devid));