diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 15554312b9..b68c79d005 100755 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -7,10 +7,10 @@ #include "AC_PID.h" const AP_Param::GroupInfo AC_PID::var_info[] PROGMEM = { - AP_GROUPINFO("P", AC_PID, _kp), - AP_GROUPINFO("I", AC_PID, _ki), - AP_GROUPINFO("D", AC_PID, _kd), - AP_GROUPINFO("IMAX", AC_PID, _imax), + AP_GROUPINFO("P", 0, AC_PID, _kp), + AP_GROUPINFO("I", 1, AC_PID, _ki), + AP_GROUPINFO("D", 2, AC_PID, _kd), + AP_GROUPINFO("IMAX", 3, AC_PID, _imax), AP_GROUPEND }; diff --git a/libraries/APM_PI/APM_PI.cpp b/libraries/APM_PI/APM_PI.cpp index d0c3ae0eef..ed4bbd64de 100644 --- a/libraries/APM_PI/APM_PI.cpp +++ b/libraries/APM_PI/APM_PI.cpp @@ -8,9 +8,9 @@ #include "APM_PI.h" const AP_Param::GroupInfo APM_PI::var_info[] PROGMEM = { - AP_GROUPINFO("P", APM_PI, _kp), - AP_GROUPINFO("I", APM_PI, _ki), - AP_GROUPINFO("IMAX", APM_PI, _imax), + AP_GROUPINFO("P", 0, APM_PI, _kp), + AP_GROUPINFO("I", 1, APM_PI, _ki), + AP_GROUPINFO("IMAX", 2, APM_PI, _imax), AP_GROUPEND }; diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index cb19e204a8..db3bd2eef5 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -2,9 +2,9 @@ #include "Compass.h" const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { - AP_GROUPINFO("ORIENT", Compass, _orientation_matrix), - AP_GROUPINFO("OFS", Compass, _offset), - AP_GROUPINFO("DEC", Compass, _declination), + AP_GROUPINFO("ORIENT", 0, Compass, _orientation_matrix), + AP_GROUPINFO("OFS", 1, Compass, _offset), + AP_GROUPINFO("DEC", 2, Compass, _declination), AP_GROUPEND }; diff --git a/libraries/AP_IMU/AP_IMU_INS.cpp b/libraries/AP_IMU/AP_IMU_INS.cpp index cc2694805e..9c8befd235 100644 --- a/libraries/AP_IMU/AP_IMU_INS.cpp +++ b/libraries/AP_IMU/AP_IMU_INS.cpp @@ -22,7 +22,7 @@ #include "AP_IMU_INS.h" const AP_Param::GroupInfo AP_IMU_INS::var_info[] PROGMEM = { - AP_GROUPINFO("CAL", AP_IMU_INS, _sensor_cal), + AP_GROUPINFO("CAL", 0, AP_IMU_INS, _sensor_cal), AP_GROUPEND }; diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 8e8499ea14..56a054729f 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -8,10 +8,10 @@ #include "PID.h" const AP_Param::GroupInfo PID::var_info[] PROGMEM = { - AP_GROUPINFO("P", PID, _kp), - AP_GROUPINFO("I", PID, _ki), - AP_GROUPINFO("D", PID, _kd), - AP_GROUPINFO("IMAX", PID, _imax), + AP_GROUPINFO("P", 0, PID, _kp), + AP_GROUPINFO("I", 1, PID, _ki), + AP_GROUPINFO("D", 2, PID, _kd), + AP_GROUPINFO("IMAX", 3, PID, _imax), AP_GROUPEND }; diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 3ec1029246..62f456a45f 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -25,11 +25,11 @@ APM_RC_Class *RC_Channel::_apm_rc; const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { - 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_GROUPINFO("MIN", 0, RC_Channel, radio_min), + AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim), + AP_GROUPINFO("MAX", 2, RC_Channel, radio_max), + AP_GROUPINFO("REV", 3, RC_Channel, _reverse), + AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone), AP_GROUPEND }; diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index b0d49df249..ac3e06e3bc 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -4,10 +4,10 @@ #include "RC_Channel_aux.h" const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { - 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_NESTEDGROUPINFO(RC_Channel, 0), + AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function), + AP_GROUPINFO("ANGLE_MIN", 2, RC_Channel_aux, angle_min), + AP_GROUPINFO("ANGLE_MAX", 3, RC_Channel_aux, angle_max), AP_GROUPEND };