Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Correct compilation with COMPASS_CAL_ENABLED off #25017

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -290,6 +290,7 @@ def __init__(self,
Feature('Other', 'SCRIPTING', 'AP_SCRIPTING_ENABLED', 'Enable LUA Scripting', 0, None),
Feature('Other', 'SLCAN', 'AP_CAN_SLCAN_ENABLED', 'Enable SLCAN serial protocol', 0, None),
Feature('Other', 'SDCARD_MISSION', 'AP_SDCARD_STORAGE_ENABLED', 'Enable storing mission on microSD cards', 0, None),
Feature('Other', 'COMPASS_CAL', 'COMPASS_CAL_ENABLED', 'Enable "tumble" compass calibration', 0, None),

# MAVLink section for mavlink features and/or message handling,
# rather than for e.g. mavlink-based sensor drivers
Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/extract_features.py
Original file line number Diff line number Diff line change
Expand Up @@ -218,6 +218,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"):

('AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'),
('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'),
('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'),
]

def progress(self, msg):
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
5 changes: 2 additions & 3 deletions libraries/AP_Compass/AP_Compass_Calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
7 changes: 7 additions & 0 deletions libraries/AP_Compass/AP_Compass_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Compass/CompassCalibrator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <AP_HAL/AP_HAL.h>
Expand Down Expand Up @@ -1153,3 +1157,5 @@ bool CompassCalibrator::right_angle_rotation(Rotation r) const
return false;
}
}

#endif // COMPASS_CAL_ENABLED
9 changes: 6 additions & 3 deletions libraries/AP_Compass/CompassCalibrator.h
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
#pragma once

#include "AP_Compass_config.h"

#if COMPASS_CAL_ENABLED

#include <AP_Math/AP_Math.h>

#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();
Expand Down Expand Up @@ -255,3 +256,5 @@ class CompassCalibrator {
// Semaphore for intermediate structure for point sample collection
HAL_Semaphore sample_sem;
};

#endif // COMPASS_CAL_ENABLED
4 changes: 3 additions & 1 deletion libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1556,7 +1556,8 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
}
break;
}


#if COMPASS_CAL_ENABLED
case AUX_FUNC::MAG_CAL: {
Compass &compass = AP::compass();
switch (ch_flag) {
Expand All @@ -1580,6 +1581,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
}
break;
}
#endif

case AUX_FUNC::ARM_EMERGENCY_STOP: {
switch (ch_flag) {
Expand Down