forked from Archive/PX4-Autopilot
Posix: fixed ioctl calls to be px4_ioctl
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
19162ba5be
commit
3f7d4de74a
|
@ -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));
|
||||
|
||||
|
|
Loading…
Reference in New Issue