From ed5cf9f7290f8c7c708d00d88407addbf3405e95 Mon Sep 17 00:00:00 2001 From: Mohammed Kabir Date: Thu, 25 May 2017 23:22:20 +0200 Subject: [PATCH] commander : simplify platform defines --- .../commander/accelerometer_calibration.cpp | 10 +++++----- src/modules/commander/gyro_calibration.cpp | 8 ++++---- src/modules/commander/mag_calibration.cpp | 15 +++++++-------- 3 files changed, 16 insertions(+), 17 deletions(-) diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 59e82a2c1f..ea38903e37 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -171,7 +171,7 @@ typedef struct { int do_accel_calibration(orb_advert_t *mavlink_log_pub) { -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_EXCELSIOR) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX int fd; #endif @@ -191,7 +191,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub) /* reset all sensors */ for (unsigned s = 0; s < max_accel_sens; s++) { -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_EXCELSIOR) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s); /* reset all offsets to zero and all scales to one */ fd = px4_open(str, 0); @@ -387,7 +387,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub) return PX4_ERROR; } -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_EXCELSIOR) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, uorb_index); fd = px4_open(str, 0); @@ -482,7 +482,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub struct accel_report report = {}; orb_copy(ORB_ID(sensor_accel), worker_data.subs[cur_accel], &report); -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX // For NuttX, we get the UNIQUE device ID from the sensor driver via an IOCTL // and match it up with the one from the uORB subscription, because the @@ -497,7 +497,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub orb_unsubscribe(worker_data.subs[cur_accel]); } -#elif defined(__PX4_QURT) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP) +#else // For the DriverFramework drivers, we fill device ID (this is the first time) by copying one report. device_id[cur_accel] = report.device_id; diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index f320a31dea..7fe1f0111b 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -243,7 +243,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) // Reset all offsets to 0 and scales to 1 (void)memcpy(&worker_data.gyro_scale[s], &gyro_scale_zero, sizeof(gyro_scale_zero)); -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_EXCELSIOR) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s); int fd = px4_open(str, 0); if (fd >= 0) { @@ -310,7 +310,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) struct gyro_report report; orb_copy(ORB_ID(sensor_gyro), worker_data.gyro_sensor_sub[cur_gyro], &report); -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX // For NuttX, we get the UNIQUE device ID from the sensor driver via an IOCTL // and match it up with the one from the uORB subscription, because the @@ -323,7 +323,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) orb_unsubscribe(worker_data.gyro_sensor_sub[cur_gyro]); } -#elif defined(__PX4_QURT) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP) +#else // For the DriverFramework drivers, we fill device ID (this is the first time) by copying one report. worker_data.device_id[cur_gyro] = report.device_id; @@ -473,7 +473,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) (void)sprintf(str, "CAL_GYRO%u_ID", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(worker_data.device_id[uorb_index]))); -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_EXCELSIOR) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX /* apply new scaling and offsets */ (void)sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, uorb_index); int fd = px4_open(str, 0); diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index a3873e51bd..4767e3a6d9 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -138,7 +138,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub) _last_mag_progress = 0; for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX // Reset mag id to mag not available (void)sprintf(str, "CAL_MAG%u_ID", cur_mag); result = param_set_no_notification(param_find(str), &(device_ids[cur_mag])); @@ -193,8 +193,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub) #endif - /* for calibration, commander will run on apps, so orb messages are used to get info from dsp */ -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX // Attempt to open mag (void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag); int fd = px4_open(str, O_RDONLY); @@ -598,7 +597,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) struct mag_report report; orb_copy(ORB_ID(sensor_mag), worker_data.sub_mag[cur_mag], &report); -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX // For NuttX, we get the UNIQUE device ID from the sensor driver via an IOCTL // and match it up with the one from the uORB subscription, because the @@ -611,7 +610,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) orb_unsubscribe(worker_data.sub_mag[cur_mag]); } -#elif defined(__PX4_QURT) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP) +#else // For the DriverFramework drivers, we fill device ID (this is the first time) by copying one report. device_ids[cur_mag] = report.device_id; @@ -792,7 +791,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) mscale.y_scale = 1.0; mscale.z_scale = 1.0; -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX int fd_mag = -1; // Set new scale @@ -821,7 +820,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) mscale.y_scale = diag_y[cur_mag]; mscale.z_scale = diag_z[cur_mag]; -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX if (px4_ioctl(fd_mag, MAGIOCSSCALE, (long unsigned int)&mscale) != PX4_OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG, cur_mag); @@ -831,7 +830,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) #endif } -#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) +#ifdef __PX4_NUTTX // Mag device no longer needed if (fd_mag >= 0) {