From 23d4473f8814f7b6b05c6610c2426d9e83e97dca Mon Sep 17 00:00:00 2001 From: bnsgeyer Date: Wed, 7 Aug 2019 22:52:41 -0400 Subject: [PATCH] Copter: tradheli-properly upgrade rsc parameters --- ArduCopter/Parameters.cpp | 45 +++++++++++++++++++++++++++++++-------- 1 file changed, 36 insertions(+), 9 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index e81bccaa9f..0e925db442 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1463,17 +1463,44 @@ void Copter::convert_tradheli_parameters(void) } } } - const AP_Param::ConversionInfo allheli_conversion_info[] = { - { Parameters::k_param_motors, 1280, AP_PARAM_INT16, "H_RSC_CRV_000" }, - { Parameters::k_param_motors, 1344, AP_PARAM_INT16, "H_RSC_CRV_025" }, - { Parameters::k_param_motors, 1408, AP_PARAM_INT16, "H_RSC_CRV_050" }, - { Parameters::k_param_motors, 1472, AP_PARAM_INT16, "H_RSC_CRV_075" }, - { Parameters::k_param_motors, 1536, AP_PARAM_INT16, "H_RSC_CRV_100" }, + + // table of rsc parameters to be converted with scaling + const AP_Param::ConversionInfo rschelipct_conversion_info[] = { + { Parameters::k_param_motors, 1280, AP_PARAM_INT16, "H_RSC_THRCRV_0" }, + { Parameters::k_param_motors, 1344, AP_PARAM_INT16, "H_RSC_THRCRV_25" }, + { Parameters::k_param_motors, 1408, AP_PARAM_INT16, "H_RSC_THRCRV_50" }, + { Parameters::k_param_motors, 1472, AP_PARAM_INT16, "H_RSC_THRCRV_75" }, + { Parameters::k_param_motors, 1536, AP_PARAM_INT16, "H_RSC_THRCRV_100" }, + { Parameters::k_param_motors, 448, AP_PARAM_INT16, "H_RSC_SETPOINT" }, + { Parameters::k_param_motors, 768, AP_PARAM_INT16, "H_RSC_CRITICAL" }, + { Parameters::k_param_motors, 832, AP_PARAM_INT16, "H_RSC_IDLE" }, + }; + // convert heli rsc parameters with scaling + uint8_t table_size = ARRAY_SIZE(rschelipct_conversion_info); + for (uint8_t i=0; iget() > 100 ) { + uint16_t tailspeed_pct = (uint16_t)(0.1f * tailspeed->get()); + AP_Param::set_and_save_by_name("H_TAIL_SPEED", tailspeed_pct ); } }