From acf437b258926b938e54b952ebf76c87bde7fdfe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 18 Sep 2023 21:53:03 +1000 Subject: [PATCH] AP_Compass: correct compilation with COMPASS_CAL_ENABLED off --- libraries/AP_Compass/AP_Compass.h | 3 --- libraries/AP_Compass/AP_Compass_Calibration.cpp | 5 ++--- libraries/AP_Compass/AP_Compass_config.h | 7 +++++++ libraries/AP_Compass/CompassCalibrator.cpp | 6 ++++++ libraries/AP_Compass/CompassCalibrator.h | 9 ++++++--- 5 files changed, 21 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 92e98f5fe1..fd37550b41 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -35,9 +35,6 @@ #endif #endif -#ifndef COMPASS_CAL_ENABLED -#define COMPASS_CAL_ENABLED 1 -#endif #ifndef COMPASS_MOT_ENABLED #define COMPASS_MOT_ENABLED 1 #endif diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 902c8e66b9..d12b77ba83 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -451,6 +451,8 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet) return result; } +#endif // COMPASS_CAL_ENABLED + /* get mag field with the effects of offsets, diagonals and off-diagonals removed @@ -571,6 +573,3 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, return MAV_RESULT_ACCEPTED; } - - -#endif // COMPASS_CAL_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_config.h b/libraries/AP_Compass/AP_Compass_config.h index 3fb16fe0d3..4f058d70a0 100644 --- a/libraries/AP_Compass/AP_Compass_config.h +++ b/libraries/AP_Compass/AP_Compass_config.h @@ -12,6 +12,13 @@ #define AP_COMPASS_DIAGONALS_ENABLED 1 #endif +#ifndef COMPASS_CAL_ENABLED +#define COMPASS_CAL_ENABLED AP_COMPASS_ENABLED +#endif + +#define COMPASS_MAX_SCALE_FACTOR 1.5 +#define COMPASS_MIN_SCALE_FACTOR (1.0/COMPASS_MAX_SCALE_FACTOR) + // Backend support #ifndef AP_COMPASS_BACKEND_DEFAULT_ENABLED #define AP_COMPASS_BACKEND_DEFAULT_ENABLED AP_COMPASS_ENABLED diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index 6b77cd9e70..57a374987c 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -57,6 +57,10 @@ * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm */ +#include "AP_Compass_config.h" + +#if COMPASS_CAL_ENABLED + #include "AP_Compass.h" #include "CompassCalibrator.h" #include @@ -1153,3 +1157,5 @@ bool CompassCalibrator::right_angle_rotation(Rotation r) const return false; } } + +#endif // COMPASS_CAL_ENABLED diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 38437f2942..90a3c4e765 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -1,14 +1,15 @@ #pragma once +#include "AP_Compass_config.h" + +#if COMPASS_CAL_ENABLED + #include #define COMPASS_CAL_NUM_SPHERE_PARAMS 4 #define COMPASS_CAL_NUM_ELLIPSOID_PARAMS 9 #define COMPASS_CAL_NUM_SAMPLES 300 // number of samples required before fitting begins -#define COMPASS_MAX_SCALE_FACTOR 1.5 -#define COMPASS_MIN_SCALE_FACTOR (1.0/COMPASS_MAX_SCALE_FACTOR) - class CompassCalibrator { public: CompassCalibrator(); @@ -255,3 +256,5 @@ private: // Semaphore for intermediate structure for point sample collection HAL_Semaphore sample_sem; }; + +#endif // COMPASS_CAL_ENABLED