From be3b1cb6ab49c58743d3427251d2633e1d966a56 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 28 May 2016 15:44:27 +0900 Subject: [PATCH] Copter: convert STB_ params to ATC_ANG_ --- ArduCopter/Parameters.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index a972fce510..52380ea124 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1059,7 +1059,10 @@ void Copter::convert_pid_parameters(void) { Parameters::k_param_pid_rate_yaw, 7, AP_PARAM_FLOAT, "ATC_RAT_YAW_ILMI" }, #endif }; - AP_Param::ConversionInfo filt_conversion_info[] = { + AP_Param::ConversionInfo angle_and_filt_conversion_info[] = { + { Parameters::k_param_p_stabilize_roll, 0, AP_PARAM_FLOAT, "ATC_ANG_RLL_P" }, + { Parameters::k_param_p_stabilize_pitch, 0, AP_PARAM_FLOAT, "ATC_ANG_PIT_P" }, + { Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" }, { Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" }, { Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" }, { Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" } @@ -1086,9 +1089,9 @@ void Copter::convert_pid_parameters(void) for (uint8_t i=0; i