AP_Param: move serial_manager parameters up to base class

This commit is contained in:
Peter Barker 2024-02-27 22:54:14 +11:00 committed by Peter Barker
parent c0a57cb447
commit 684b621b8c
2 changed files with 17 additions and 1 deletions

View File

@ -2087,6 +2087,13 @@ void AP_Param::convert_g2_objects(const void *g2, const G2ObjectConversion g2_co
} }
} }
void AP_Param::convert_toplevel_objects(const TopLevelObjectConversion conversions[], uint8_t num_conversions)
{
for (uint8_t i=0; i<num_conversions; i++) {
const auto &c { conversions[i] };
convert_class(c.old_index, c.object_pointer, c.var_info, 0, true);
}
}
/* /*
convert width of a parameter, allowing update to wider scalar values convert width of a parameter, allowing update to wider scalar values

View File

@ -477,10 +477,19 @@ public:
struct G2ObjectConversion { struct G2ObjectConversion {
void *object_pointer; void *object_pointer;
const struct AP_Param::GroupInfo *var_info; const struct AP_Param::GroupInfo *var_info;
uint16_t old_index; // Old parameter index in g uint16_t old_index; // Old parameter index in g2
}; };
static void convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions); static void convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions);
// convert an object which was stored in a vehicle's top-level
// Parameters object into a new object in AP_Vehicle.cpp:
struct TopLevelObjectConversion {
void *object_pointer;
const struct AP_Param::GroupInfo *var_info;
uint16_t old_index; // Old parameter index in g
};
static void convert_toplevel_objects(const TopLevelObjectConversion g2_conversions[], uint8_t num_conversions);
/* /*
convert width of a parameter, allowing update to wider scalar convert width of a parameter, allowing update to wider scalar
values without changing the parameter indexes. This will return values without changing the parameter indexes. This will return