mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: User parameters implementation
This commit is contained in:
parent
0f10d2316a
commit
af6303c82b
@ -66,3 +66,4 @@
|
|||||||
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
|
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
|
||||||
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
|
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
|
||||||
//#define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches
|
//#define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches
|
||||||
|
//#define USER_PARAMS_ENABLED ENABLED // to enable user parameters
|
||||||
|
@ -171,6 +171,9 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Local modules
|
// Local modules
|
||||||
|
#ifdef USER_PARAMS_ENABLED
|
||||||
|
#include "UserParameters.h"
|
||||||
|
#endif
|
||||||
#include "Parameters.h"
|
#include "Parameters.h"
|
||||||
#if ADSB_ENABLED == ENABLED
|
#if ADSB_ENABLED == ENABLED
|
||||||
#include "avoidance_adsb.h"
|
#include "avoidance_adsb.h"
|
||||||
|
@ -944,6 +944,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),
|
AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USER_PARAMS_ENABLED
|
||||||
|
AP_SUBGROUPINFO(follow, "USR", 28, ParametersG2, UserParameters),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -1009,6 +1013,9 @@ ParametersG2::ParametersG2(void)
|
|||||||
#if MODE_FOLLOW_ENABLED == ENABLED
|
#if MODE_FOLLOW_ENABLED == ENABLED
|
||||||
,follow()
|
,follow()
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef USER_PARAMS_ENABLED
|
||||||
|
,user_parameters()
|
||||||
|
#endif
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
@ -581,6 +581,11 @@ public:
|
|||||||
AP_Follow follow;
|
AP_Follow follow;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USER_PARAMS_ENABLED
|
||||||
|
// User custom parameters
|
||||||
|
UserParameters user_parameters;
|
||||||
|
#endif
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const AP_Param::Info var_info[];
|
extern const AP_Param::Info var_info[];
|
||||||
|
13
ArduCopter/UserParameters.cpp
Normal file
13
ArduCopter/UserParameters.cpp
Normal file
@ -0,0 +1,13 @@
|
|||||||
|
#include "UserParameters.h"
|
||||||
|
|
||||||
|
// "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
|
||||||
|
};
|
22
ArduCopter/UserParameters.h
Normal file
22
ArduCopter/UserParameters.h
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_Param/AP_Param.h>
|
||||||
|
|
||||||
|
class UserParameters {
|
||||||
|
|
||||||
|
public:
|
||||||
|
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;
|
||||||
|
AP_Int16 _int16;
|
||||||
|
AP_Float _float;
|
||||||
|
};
|
Loading…
Reference in New Issue
Block a user