mirror of https://github.com/ArduPilot/ardupilot
Plane: use separate definition for TUNE_PARM
this allows the parameter docs to be separated
This commit is contained in:
parent
d72df80968
commit
35ef20b23a
|
@ -1116,7 +1116,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||||
GOBJECT(quadplane, "Q_", QuadPlane),
|
GOBJECT(quadplane, "Q_", QuadPlane),
|
||||||
|
|
||||||
// @Group: TUNE_
|
// @Group: TUNE_
|
||||||
// @Path: tuning.cpp
|
// @Path: tuning.cpp,../libraries/AP_Tuning/AP_Tuning.cpp
|
||||||
GOBJECT(tuning, "TUNE_", AP_Tuning_Plane),
|
GOBJECT(tuning, "TUNE_", AP_Tuning_Plane),
|
||||||
|
|
||||||
// @Group: Q_A_
|
// @Group: Q_A_
|
||||||
|
|
|
@ -2,6 +2,25 @@
|
||||||
|
|
||||||
#include "Plane.h"
|
#include "Plane.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
the vehicle class has its own var table for TUNE_PARAM so it can
|
||||||
|
have separate parameter docs for the list of available parameters
|
||||||
|
*/
|
||||||
|
const AP_Param::GroupInfo AP_Tuning_Plane::var_info[] = {
|
||||||
|
// @Param: PARAM
|
||||||
|
// @DisplayName: Transmitter tuning parameter or set of parameters
|
||||||
|
// @Description: This sets which parameter or set of parameters will be tuned. Values greater than 100 indicate a set of parameters rather than a single parameter. Parameters less than 50 are for QuadPlane vertical lift motors only.
|
||||||
|
// @Values: 0:None,1:RateRollPI,2:RateRollP,3:RateRollI,4:RateRollD,5:RatePitchPI,6:RatePitchP,7:RatePitchI,8:RatePitchD,9:RateYawPI,10:RateYawP,11:RateYawI,12:RateYawD,13:AngleRollP,14:AnglePitchP,15:AngleYawP,16:PosXYP,17:PosZP,18:VelXYP,19:VelXYI,20:VelZP,21:AccelZP,22:AccelZI,23:AccelZD,50:FixedWingRollP,51:FixedWingRollI,52:FixedWingRollD,53:FixedWingRollFF,54:FixedWingPitchP,55:FixedWingPitchI,56:FixedWingPitchD,57:FixedWingPitchFF
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("PARAM", 1, AP_Tuning_Plane, parmset, 0),
|
||||||
|
|
||||||
|
// the rest of the parameters are from AP_Tuning
|
||||||
|
AP_NESTEDGROUPINFO(AP_Tuning, 0),
|
||||||
|
|
||||||
|
AP_GROUPEND
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
tables of tuning sets
|
tables of tuning sets
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -18,6 +18,8 @@ public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_Tuning_Plane(void) : AP_Tuning(tuning_sets, tuning_names) {}
|
AP_Tuning_Plane(void) : AP_Tuning(tuning_sets, tuning_names) {}
|
||||||
|
|
||||||
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
// individual tuning parameters
|
// individual tuning parameters
|
||||||
|
|
Loading…
Reference in New Issue