From 46e560f3f6bcfb35c0765640e90d9d9d741689f1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 3 Jan 2023 17:22:22 +0000 Subject: [PATCH] AC_AttitudeControl: CommandModel: use new defualt pattern --- libraries/AC_AttitudeControl/AC_CommandModel.cpp | 14 +++++++------- libraries/AC_AttitudeControl/AC_CommandModel.h | 4 ++++ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.cpp b/libraries/AC_AttitudeControl/AC_CommandModel.cpp index 6646161e1a..0efe05f36c 100644 --- a/libraries/AC_AttitudeControl/AC_CommandModel.cpp +++ b/libraries/AC_AttitudeControl/AC_CommandModel.cpp @@ -15,7 +15,7 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = { // @Units: deg/s // @Range: 1 360 // @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 // @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 // @Range: -0.5 1.0 // @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 // @DisplayName: Rate control input time constant @@ -33,17 +33,17 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = { // @Increment: 0.01 // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp // @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 }; // 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); - rate.set_and_default(initial_rate); - expo.set_and_default(initial_expo); - rate_tc.set_and_default(initial_tc); } diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.h b/libraries/AC_AttitudeControl/AC_CommandModel.h index dd99031474..6076ba65b4 100644 --- a/libraries/AC_AttitudeControl/AC_CommandModel.h +++ b/libraries/AC_AttitudeControl/AC_CommandModel.h @@ -29,5 +29,9 @@ protected: AP_Float rate; // maximum rate AP_Float expo; // expo shaping +private: + const float default_rate_tc; + const float default_rate; + const float default_expo; };