diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 826c308a46..0beaeb860a 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2072,6 +2072,8 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer, flush(); } +// convert an object which was stored in a vehicle's G2 into a new +// object in AP_Vehicle.cpp: void AP_Param::convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions) { // Find G2's Top Level Key diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 2aeb19a8a2..1a9284a71e 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -472,6 +472,8 @@ public: // 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 an object which was stored in a vehicle's G2 into a new + // object in AP_Vehicle.cpp: struct G2ObjectConversion { void *object_pointer; const struct AP_Param::GroupInfo *var_info;