mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: use AP_GPS_ENABLED to exclude more code when GPS not compiled in
This commit is contained in:
parent
babdb3625a
commit
9a054876ff
|
@ -453,6 +453,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)
|
|||
|
||||
#endif // COMPASS_CAL_ENABLED
|
||||
|
||||
#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
|
||||
/*
|
||||
get mag field with the effects of offsets, diagonals and
|
||||
off-diagonals removed
|
||||
|
@ -573,3 +574,5 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
|
|||
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
#endif // AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#include <AP_ExternalAHRS/AP_ExternalAHRS_config.h>
|
||||
#include <AP_MSP/msp.h>
|
||||
#include <AP_AHRS/AP_AHRS_config.h>
|
||||
#include <AP_GPS/AP_GPS_config.h>
|
||||
|
||||
#ifndef AP_COMPASS_ENABLED
|
||||
#define AP_COMPASS_ENABLED 1
|
||||
|
@ -17,6 +18,10 @@
|
|||
#define COMPASS_CAL_ENABLED AP_COMPASS_ENABLED && AP_AHRS_DCM_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
|
||||
#define AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED AP_GPS_ENABLED
|
||||
#endif
|
||||
|
||||
#define COMPASS_MAX_SCALE_FACTOR 1.5
|
||||
#define COMPASS_MIN_SCALE_FACTOR (1.0/COMPASS_MAX_SCALE_FACTOR)
|
||||
|
||||
|
|
Loading…
Reference in New Issue