From f7db538220a2903b41bb735235ff166cc541b24b Mon Sep 17 00:00:00 2001 From: Grant Morphett Date: Tue, 28 Nov 2017 08:13:53 +1100 Subject: [PATCH] APM_Control: Fixed the subparam indexs to start at 1 AFAIK there is still a bug in ArduPilot where subparams should not start at index 0. This is due to the way the index math and bit shifing works as it incorrectly offsets all 0 index params to 0. We allow 2 levels of sub params - 3 levels in total. So params, sub params and sub sub params. The 0 parameter in all those is unfortunately always references param[0]. So param[0] and subparam[0] and subsubparam[0] will reference the same parameter value. Its why we always say start the index from 1 as the math and bitshifting then works correctly. Yeah this is worded badly - hard to explain. --- libraries/APM_Control/AR_AttitudeControl.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index fb33fc3983..ac3bed498a 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -21,13 +21,6 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { - // @Param: _STR_ANG_P - // @DisplayName: Steering control angle P gain - // @Description: Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec) - // @Range: 1.000 10.000 - // @User: Standard - AP_SUBGROUPINFO(_steer_angle_p, "_STR_ANG_", 0, AR_AttitudeControl, AC_P), - // @Param: _STR_RATE_P // @DisplayName: Steering control rate P gain // @Description: Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1) @@ -117,6 +110,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @User: Standard AP_GROUPINFO("_STOP_SPEED", 5, AR_AttitudeControl, _stop_speed, AR_ATTCONTROL_STOP_SPEED_DEFAULT), + // @Param: _STR_ANG_P + // @DisplayName: Steering control angle P gain + // @Description: Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec) + // @Range: 1.000 10.000 + // @User: Standard + AP_SUBGROUPINFO(_steer_angle_p, "_STR_ANG_", 6, AR_AttitudeControl, AC_P), + AP_GROUPEND };