diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 8d77c5ebbe..f222584183 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -8,10 +8,10 @@ */ #define GSCALAR(v, name, def) { plane.g.v.vtype, name, Parameters::k_param_ ## v, &plane.g.v, {def_value : def} } -#define ASCALAR(v, name, def) { plane.aparm.v.vtype, name, Parameters::k_param_ ## v, &plane.aparm.v, {def_value : def} } +#define ASCALAR(v, name, def) { plane.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&plane.aparm.v, {def_value : def} } #define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &plane.g.v, {group_info : class::var_info} } -#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &plane.v, {group_info : class::var_info} } -#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &plane.v, {group_info : class::var_info} } +#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&plane.v, {group_info : class::var_info} } +#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&plane.v, {group_info : class::var_info} } const AP_Param::Info Plane::var_info[] PROGMEM = { // @Param: FORMAT_VERSION @@ -1164,12 +1164,6 @@ const AP_Param::Info Plane::var_info[] PROGMEM = { GOBJECT(obc, "AFS_", APM_OBC), #endif -#if AP_AHRS_NAVEKF_AVAILABLE - // @Group: EKF_ - // @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp - GOBJECTN(ahrs.get_NavEKF(), NavEKF, "EKF_", NavEKF), -#endif - #if OPTFLOW == ENABLED // @Group: FLOW // @Path: ../libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -1184,6 +1178,12 @@ const AP_Param::Info Plane::var_info[] PROGMEM = { // @Path: ../libraries/AP_Rally/AP_Rally.cpp GOBJECT(rally, "RALLY_", AP_Rally), +#if AP_AHRS_NAVEKF_AVAILABLE + // @Group: EKF_ + // @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp + GOBJECTN(ahrs.get_NavEKF_const(), NavEKF, "EKF_", NavEKF), +#endif + AP_VAREND };