Copter: set paraam default for user parameters

This commit is contained in:
rishabsingh3003 2022-12-23 11:42:26 +05:30 committed by Tom Pittenger
parent 175c2c950e
commit a57ed97ba1
2 changed files with 11 additions and 6 deletions

View File

@ -1,13 +1,18 @@
#include "UserParameters.h"
// "USR" + 13 chars remaining for param name
// "USR" + 13 chars remaining for param name
const AP_Param::GroupInfo UserParameters::var_info[] = {
// Put your parameters definition here
// Note the maximum length of parameter name is 13 chars
AP_GROUPINFO("_INT8", 0, UserParameters, _int8, 0),
AP_GROUPINFO("_INT16", 1, UserParameters, _int16, 0),
AP_GROUPINFO("_FLOAT", 2, UserParameters, _float, 0),
AP_GROUPEND
};
UserParameters::UserParameters()
{
AP_Param::setup_object_defaults(this, var_info);
}

View File

@ -5,15 +5,15 @@
class UserParameters {
public:
UserParameters() {}
UserParameters();
static const struct AP_Param::GroupInfo var_info[];
// Put accessors to your parameter variables here
// UserCode usage example: g2.user_parameters.get_int8Param()
AP_Int8 get_int8Param() const { return _int8; }
AP_Int16 get_int16Param() const { return _int16; }
AP_Float get_floatParam() const { return _float; }
private:
// Put your parameter variable definitions here
AP_Int8 _int8;