mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning: add and use AP_TUNING_ENABLED
This commit is contained in:
parent
1208938d3b
commit
fc722b5efc
|
@ -91,7 +91,10 @@
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
#include "GCS_Plane.h"
|
#include "GCS_Plane.h"
|
||||||
#include "quadplane.h"
|
#include "quadplane.h"
|
||||||
|
#include <AP_Tuning/AP_Tuning_config.h>
|
||||||
|
#if AP_TUNING_ENABLED
|
||||||
#include "tuning.h"
|
#include "tuning.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
// Configuration
|
// Configuration
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
|
@ -793,8 +796,10 @@ private:
|
||||||
QuadPlane quadplane{ahrs};
|
QuadPlane quadplane{ahrs};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_TUNING_ENABLED
|
||||||
// support for transmitter tuning
|
// support for transmitter tuning
|
||||||
AP_Tuning_Plane tuning;
|
AP_Tuning_Plane tuning;
|
||||||
|
#endif
|
||||||
|
|
||||||
static const struct LogStructure log_structure[];
|
static const struct LogStructure log_structure[];
|
||||||
|
|
||||||
|
|
|
@ -210,8 +210,10 @@ void Plane::read_radio()
|
||||||
quadplane.tailsitter.check_input();
|
quadplane.tailsitter.check_input();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_TUNING_ENABLED
|
||||||
// check for transmitter tuning changes
|
// check for transmitter tuning changes
|
||||||
tuning.check_input(control_mode->mode_number());
|
tuning.check_input(control_mode->mode_number());
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t Plane::rudder_input(void)
|
int16_t Plane::rudder_input(void)
|
||||||
|
|
|
@ -1,3 +1,7 @@
|
||||||
|
#include "AP_Tuning_config.h"
|
||||||
|
|
||||||
|
#if AP_TUNING_ENABLED
|
||||||
|
|
||||||
#include "AP_Tuning.h"
|
#include "AP_Tuning.h"
|
||||||
|
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
@ -334,3 +338,5 @@ const char *AP_Tuning::get_tuning_name(uint8_t parm)
|
||||||
}
|
}
|
||||||
return "UNKNOWN";
|
return "UNKNOWN";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_TUNING_ENABLED
|
||||||
|
|
|
@ -1,5 +1,9 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Tuning_config.h"
|
||||||
|
|
||||||
|
#if AP_TUNING_ENABLED
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
|
||||||
#include "stdint.h"
|
#include "stdint.h"
|
||||||
|
@ -100,3 +104,5 @@ protected:
|
||||||
// parmset is in vehicle subclass var table
|
// parmset is in vehicle subclass var table
|
||||||
AP_Int16 parmset;
|
AP_Int16 parmset;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_TUNING_ENABLED
|
||||||
|
|
|
@ -0,0 +1,7 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#ifndef AP_TUNING_ENABLED
|
||||||
|
#define AP_TUNING_ENABLED 1
|
||||||
|
#endif
|
Loading…
Reference in New Issue