diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 20a28c7e4a..afa0188dfa 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1922,7 +1922,6 @@ bool AP_Param::find_old_parameter(const struct ConversionInfo *info, AP_Param *v return true; } - #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wformat" // convert one old vehicle parameter to new object parameter @@ -1983,11 +1982,17 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc #pragma GCC diagnostic pop -// convert old vehicle parameters to new object parametersv +// convert old vehicle parameters to new object parameters void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags) +{ + convert_old_parameters_scaled(conversion_table, table_size, 1.0f,flags); +} + +// convert old vehicle parameters to new object parameters with scaling - assumes all parameters will have the same scaling factor +void AP_Param::convert_old_parameters_scaled(const struct ConversionInfo *conversion_table, uint8_t table_size, float scaler, uint8_t flags) { for (uint8_t i=0; icast_to_float(old_ptype); - set_value(new_ptype, this, old_float_value); + set_value(new_ptype, this, old_float_value*scale_factor); // force save as the new type save(true); @@ -2098,7 +2103,6 @@ bool AP_Param::convert_parameter_width(ap_var_type old_ptype) return true; } - /* set a parameter to a float value */ diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 40aebd852c..4fed080f07 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -467,13 +467,18 @@ public: // convert old vehicle parameters to new object parameters static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0); + // convert old vehicle parameters to new object parameters with scaling - assumes we use the same scaling factor for all values in the table + static void convert_old_parameters_scaled(const ConversionInfo *conversion_table, uint8_t table_size, float scaler, uint8_t flags); /* convert width of a parameter, allowing update to wider scalar values without changing the parameter indexes. This will return true if the parameter was converted from an old parameter value */ - bool convert_parameter_width(ap_var_type old_ptype); + bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0); + bool convert_centi_parameter(ap_var_type old_ptype) { + return convert_parameter_width(old_ptype, 0.01f); + } // convert a single parameter with scaling enum {