mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControl: CommandModel: use new defualt pattern
This commit is contained in:
parent
6cd5cf8195
commit
46e560f3f6
|
@ -15,7 +15,7 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = {
|
||||||
// @Units: deg/s
|
// @Units: deg/s
|
||||||
// @Range: 1 360
|
// @Range: 1 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RATE", 1, AC_CommandModel, rate, 202.5),
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("RATE", 1, AC_CommandModel, rate, default_rate),
|
||||||
|
|
||||||
// @Param: EXPO
|
// @Param: EXPO
|
||||||
// @DisplayName: Controlled Expo
|
// @DisplayName: Controlled Expo
|
||||||
|
@ -23,7 +23,7 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = {
|
||||||
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
|
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
|
||||||
// @Range: -0.5 1.0
|
// @Range: -0.5 1.0
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EXPO", 2, AC_CommandModel, expo, 0),
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("EXPO", 2, AC_CommandModel, expo, default_expo),
|
||||||
|
|
||||||
// @Param: RATE_TC
|
// @Param: RATE_TC
|
||||||
// @DisplayName: Rate control input time constant
|
// @DisplayName: Rate control input time constant
|
||||||
|
@ -33,17 +33,17 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = {
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
|
// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RATE_TC", 3, AC_CommandModel, rate_tc, 0.05f),
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("RATE_TC", 3, AC_CommandModel, rate_tc, default_rate_tc),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc)
|
AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc) :
|
||||||
|
default_rate(initial_rate),
|
||||||
|
default_expo(initial_expo),
|
||||||
|
default_rate_tc(initial_tc)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
rate.set_and_default(initial_rate);
|
|
||||||
expo.set_and_default(initial_expo);
|
|
||||||
rate_tc.set_and_default(initial_tc);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -29,5 +29,9 @@ protected:
|
||||||
AP_Float rate; // maximum rate
|
AP_Float rate; // maximum rate
|
||||||
AP_Float expo; // expo shaping
|
AP_Float expo; // expo shaping
|
||||||
|
|
||||||
|
private:
|
||||||
|
const float default_rate_tc;
|
||||||
|
const float default_rate;
|
||||||
|
const float default_expo;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue