mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: build_options.py: include fixed-yaw and in-flight learning options
This commit is contained in:
parent
4a1adc69da
commit
857547ba55
@ -160,6 +160,8 @@ BUILD_OPTIONS = [
|
||||
Feature('Compass', 'QMC5883L', 'AP_COMPASS_QMC5883L_ENABLED', 'Enable QMC5883L compasses', 1, None),
|
||||
Feature('Compass', 'RM3100', 'AP_COMPASS_RM3100_ENABLED', 'Enable RM3100 compasses', 1, None),
|
||||
Feature('Compass', 'DRONECAN_COMPASS', 'AP_COMPASS_DRONECAN_ENABLED', 'Enable DroneCAN compasses', 0, None),
|
||||
Feature('Compass', 'FixedYawCal', 'AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Enable Fixed-Yaw Compass Calibration', 1, None), # noqa
|
||||
Feature('Compass', 'CompassLearn', 'COMPASS_LEARN_ENABLED', 'Enable In-Flight Compass Learning', 1, "FixedYawCal"),
|
||||
|
||||
Feature('Gimbal', 'MOUNT', 'HAL_MOUNT_ENABLED', 'Enable Mount', 0, None),
|
||||
Feature('Gimbal', 'ALEXMOS', 'HAL_MOUNT_ALEXMOS_ENABLED', 'Enable Alexmos Gimbal', 0, "MOUNT"),
|
||||
|
@ -242,6 +242,8 @@ class ExtractFeatures(object):
|
||||
('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'),
|
||||
('HAL_BUTTON_ENABLED', 'AP_Button::update'),
|
||||
('HAL_LOGGING_ENABLED', 'AP_Logger::Init'),
|
||||
('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'AP_Compass::mag_cal_fixed_yaw'),
|
||||
('COMPASS_LEARN_ENABLED', 'CompassLearn::update'),
|
||||
]
|
||||
|
||||
def progress(self, msg):
|
||||
|
Loading…
Reference in New Issue
Block a user