AP_Compass: correct compilation with COMPASS_CAL_ENABLED off

This commit is contained in:
Peter Barker 2023-09-18 21:53:03 +10:00 committed by Peter Barker
parent 12a06ee0ae
commit acf437b258
5 changed files with 21 additions and 9 deletions

View File

@ -35,9 +35,6 @@
#endif #endif
#endif #endif
#ifndef COMPASS_CAL_ENABLED
#define COMPASS_CAL_ENABLED 1
#endif
#ifndef COMPASS_MOT_ENABLED #ifndef COMPASS_MOT_ENABLED
#define COMPASS_MOT_ENABLED 1 #define COMPASS_MOT_ENABLED 1
#endif #endif

View File

@ -451,6 +451,8 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)
return result; return result;
} }
#endif // COMPASS_CAL_ENABLED
/* /*
get mag field with the effects of offsets, diagonals and get mag field with the effects of offsets, diagonals and
off-diagonals removed 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; return MAV_RESULT_ACCEPTED;
} }
#endif // COMPASS_CAL_ENABLED

View File

@ -12,6 +12,13 @@
#define AP_COMPASS_DIAGONALS_ENABLED 1 #define AP_COMPASS_DIAGONALS_ENABLED 1
#endif #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 // Backend support
#ifndef AP_COMPASS_BACKEND_DEFAULT_ENABLED #ifndef AP_COMPASS_BACKEND_DEFAULT_ENABLED
#define AP_COMPASS_BACKEND_DEFAULT_ENABLED AP_COMPASS_ENABLED #define AP_COMPASS_BACKEND_DEFAULT_ENABLED AP_COMPASS_ENABLED

View File

@ -57,6 +57,10 @@
* http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm
*/ */
#include "AP_Compass_config.h"
#if COMPASS_CAL_ENABLED
#include "AP_Compass.h" #include "AP_Compass.h"
#include "CompassCalibrator.h" #include "CompassCalibrator.h"
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -1153,3 +1157,5 @@ bool CompassCalibrator::right_angle_rotation(Rotation r) const
return false; return false;
} }
} }
#endif // COMPASS_CAL_ENABLED

View File

@ -1,14 +1,15 @@
#pragma once #pragma once
#include "AP_Compass_config.h"
#if COMPASS_CAL_ENABLED
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#define COMPASS_CAL_NUM_SPHERE_PARAMS 4 #define COMPASS_CAL_NUM_SPHERE_PARAMS 4
#define COMPASS_CAL_NUM_ELLIPSOID_PARAMS 9 #define COMPASS_CAL_NUM_ELLIPSOID_PARAMS 9
#define COMPASS_CAL_NUM_SAMPLES 300 // number of samples required before fitting begins #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 { class CompassCalibrator {
public: public:
CompassCalibrator(); CompassCalibrator();
@ -255,3 +256,5 @@ private:
// Semaphore for intermediate structure for point sample collection // Semaphore for intermediate structure for point sample collection
HAL_Semaphore sample_sem; HAL_Semaphore sample_sem;
}; };
#endif // COMPASS_CAL_ENABLED