Platform header file cleanup and consolidation

Removed obsolete porting cruft from px4_XXX.h files and merged the
POSIX changes in PreflightCheck_posix.cpp back to PreflightCheck.cpp

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois
2015-04-24 11:45:14 -07:00
parent 16d6068bfd
commit 20d35e33da
9 changed files with 47 additions and 399 deletions

View File

@@ -41,6 +41,7 @@
*/
#include <px4_config.h>
#include <px4_posix.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
@@ -74,7 +75,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional)
char s[30];
sprintf(s, "%s%u", MAG_BASE_DEVICE_PATH, instance);
int fd = open(s, 0);
int fd = px4_open(s, 0);
if (fd < 0) {
if (!optional) {
@@ -87,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));
@@ -98,7 +99,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional)
goto out;
}
ret = ioctl(fd, MAGIOCSELFTEST, 0);
ret = px4_ioctl(fd, MAGIOCSELFTEST, 0);
if (ret != OK) {
mavlink_and_console_log_critical(mavlink_fd,
@@ -108,7 +109,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional)
}
out:
close(fd);
px4_close(fd);
return success;
}
@@ -118,7 +119,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
char s[30];
sprintf(s, "%s%u", ACCEL_BASE_DEVICE_PATH, instance);
int fd = open(s, O_RDONLY);
int fd = px4_open(s, O_RDONLY);
if (fd < 0) {
if (!optional) {
@@ -131,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));
@@ -142,7 +143,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
goto out;
}
ret = ioctl(fd, ACCELIOCSELFTEST, 0);
ret = px4_ioctl(fd, ACCELIOCSELFTEST, 0);
if (ret != OK) {
mavlink_and_console_log_critical(mavlink_fd,
@@ -154,7 +155,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
if (dynamic) {
/* check measurement result range */
struct accel_report acc;
ret = read(fd, &acc, sizeof(acc));
ret = px4_read(fd, &acc, sizeof(acc));
if (ret == sizeof(acc)) {
/* evaluate values */
@@ -175,7 +176,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
}
out:
close(fd);
px4_close(fd);
return success;
}
@@ -185,7 +186,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional)
char s[30];
sprintf(s, "%s%u", GYRO_BASE_DEVICE_PATH, instance);
int fd = open(s, 0);
int fd = px4_open(s, 0);
if (fd < 0) {
if (!optional) {
@@ -198,7 +199,7 @@ static bool gyroCheck(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_GYRO%u_ID", instance);
param_get(param_find(s), &(calibration_devid));
@@ -209,7 +210,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional)
goto out;
}
ret = ioctl(fd, GYROIOCSELFTEST, 0);
ret = px4_ioctl(fd, GYROIOCSELFTEST, 0);
if (ret != OK) {
mavlink_and_console_log_critical(mavlink_fd,
@@ -219,7 +220,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional)
}
out:
close(fd);
px4_close(fd);
return success;
}
@@ -229,7 +230,7 @@ static bool baroCheck(int mavlink_fd, unsigned instance, bool optional)
char s[30];
sprintf(s, "%s%u", BARO_BASE_DEVICE_PATH, instance);
int fd = open(s, 0);
int fd = px4_open(s, 0);
if (fd < 0) {
if (!optional) {
@@ -240,7 +241,7 @@ static bool baroCheck(int mavlink_fd, unsigned instance, bool optional)
return false;
}
close(fd);
px4_close(fd);
return success;
}