diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index 848de698d0..cb19e204a8 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -2,10 +2,10 @@ #include "Compass.h" const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { - { AP_PARAM_MATRIX3F, "", VAROFFSET(Compass, _orientation_matrix) }, - { AP_PARAM_VECTOR3F, "", VAROFFSET(Compass, _offset) }, - { AP_PARAM_VECTOR3F, "DEC", VAROFFSET(Compass, _declination) }, - { AP_PARAM_NONE, "" } + AP_GROUPINFO("ORIENT", Compass, _orientation_matrix), + AP_GROUPINFO("OFS", Compass, _offset), + AP_GROUPINFO("DEC", Compass, _declination), + AP_GROUPEND }; // Default constructor. diff --git a/libraries/AP_IMU/AP_IMU_INS.cpp b/libraries/AP_IMU/AP_IMU_INS.cpp index 4a828da3d0..cc2694805e 100644 --- a/libraries/AP_IMU/AP_IMU_INS.cpp +++ b/libraries/AP_IMU/AP_IMU_INS.cpp @@ -22,8 +22,8 @@ #include "AP_IMU_INS.h" const AP_Param::GroupInfo AP_IMU_INS::var_info[] PROGMEM = { - { AP_PARAM_VECTOR3F, "", VAROFFSET(AP_IMU_INS, _sensor_cal) }, - { AP_PARAM_NONE, "" } + AP_GROUPINFO("CAL", AP_IMU_INS, _sensor_cal), + AP_GROUPEND }; void diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 67922cb75d..f82a873242 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -8,11 +8,11 @@ #include "PID.h" const AP_Param::GroupInfo PID::var_info[] PROGMEM = { - { AP_PARAM_FLOAT, "P", VAROFFSET(PID, _kp) }, - { AP_PARAM_FLOAT, "I", VAROFFSET(PID, _ki) }, - { AP_PARAM_FLOAT, "D", VAROFFSET(PID, _kd) }, - { AP_PARAM_INT16, "IMAX", VAROFFSET(PID, _imax) }, - { AP_PARAM_NONE, "" } + AP_GROUPINFO("P", PID, _kp), + AP_GROUPINFO("I", PID, _ki), + AP_GROUPINFO("D", PID, _kd), + AP_GROUPINFO("IMAX", PID, _imax), + AP_GROUPEND }; long diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 4445f4d3bc..3ec1029246 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -25,12 +25,12 @@ APM_RC_Class *RC_Channel::_apm_rc; const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { - { AP_PARAM_INT16, "MIN", VAROFFSET(RC_Channel, radio_min) }, - { AP_PARAM_INT16, "TRIM", VAROFFSET(RC_Channel, radio_trim) }, - { AP_PARAM_INT16, "MAX", VAROFFSET(RC_Channel, radio_max) }, - { AP_PARAM_INT8, "REV", VAROFFSET(RC_Channel, _reverse) }, - { AP_PARAM_INT16, "DZ", VAROFFSET(RC_Channel, _dead_zone) }, - { AP_PARAM_NONE, "" } + AP_GROUPINFO("MIN", RC_Channel, radio_min), + AP_GROUPINFO("TRIM", RC_Channel, radio_trim), + AP_GROUPINFO("MAX", RC_Channel, radio_max), + AP_GROUPINFO("REV", RC_Channel, _reverse), + AP_GROUPINFO("DZ", RC_Channel, _dead_zone), + AP_GROUPEND }; // setup the control preferences diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 8071272cdf..b0d49df249 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -4,15 +4,11 @@ #include "RC_Channel_aux.h" const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { - { AP_PARAM_INT16, "MIN", VAROFFSET(RC_Channel_aux, radio_min) }, - { AP_PARAM_INT16, "TRIM", VAROFFSET(RC_Channel_aux, radio_trim) }, - { AP_PARAM_INT16, "MAX", VAROFFSET(RC_Channel_aux, radio_max) }, - { AP_PARAM_INT8, "REV", VAROFFSET(RC_Channel_aux, _reverse) }, - { AP_PARAM_INT16, "DZ", VAROFFSET(RC_Channel_aux, _dead_zone) }, - { AP_PARAM_INT8, "FUNCTION", VAROFFSET(RC_Channel_aux, function) }, - { AP_PARAM_INT8, "ANGLE_MIN", VAROFFSET(RC_Channel_aux, angle_min) }, - { AP_PARAM_INT8, "ANGLE_MAX", VAROFFSET(RC_Channel_aux, angle_max) }, - { AP_PARAM_NONE, "" } + AP_NESTEDGROUPINFO(RC_Channel), + AP_GROUPINFO("FUNCTION", RC_Channel_aux, function), + AP_GROUPINFO("ANGLE_MIN", RC_Channel_aux, angle_min), + AP_GROUPINFO("ANGLE_MAX", RC_Channel_aux, angle_max), + AP_GROUPEND }; RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function