Plane: use AP_TUNING_ENABLED

This commit is contained in:
Peter Barker 2023-09-19 19:51:43 +10:00 committed by Peter Barker
parent fc722b5efc
commit fbb0601408
3 changed files with 15 additions and 0 deletions

View File

@ -800,9 +800,11 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(quadplane, "Q_", QuadPlane),
#endif
#if AP_TUNING_ENABLED
// @Group: TUNE_
// @Path: tuning.cpp,../libraries/AP_Tuning/AP_Tuning.cpp
GOBJECT(tuning, "TUNE_", AP_Tuning_Plane),
#endif
#if HAL_QUADPLANE_ENABLED
// @Group: Q_A_

View File

@ -1,3 +1,7 @@
#include <AP_Tuning/AP_Tuning_config.h>
#if AP_TUNING_ENABLED
#include "Plane.h"
/*
@ -305,3 +309,4 @@ void AP_Tuning_Plane::reload_value(uint8_t parm)
}
}
#endif // AP_TUNING_ENABLED

View File

@ -1,3 +1,9 @@
#pragma once
#include <AP_Tuning/AP_Tuning_config.h>
#if AP_TUNING_ENABLED
#include <AP_Tuning/AP_Tuning.h>
/*
@ -108,3 +114,5 @@ private:
// mask of what params have been set
uint64_t have_set;
};
#endif // AP_TUNING_ENABLED