mirror of https://github.com/ArduPilot/ardupilot
AP_Param: add convert_bitmask_parameter_width method
This commit is contained in:
parent
26ec2ae952
commit
cd0bdda93d
|
@ -2099,7 +2099,7 @@ void AP_Param::convert_toplevel_objects(const TopLevelObjectConversion conversio
|
||||||
convert width of a parameter, allowing update to wider scalar values
|
convert width of a parameter, allowing update to wider scalar values
|
||||||
without changing the parameter indexes
|
without changing the parameter indexes
|
||||||
*/
|
*/
|
||||||
bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor)
|
bool AP_Param::_convert_parameter_width(ap_var_type old_ptype, float scale_factor, bool bitmask)
|
||||||
{
|
{
|
||||||
if (configured_in_storage()) {
|
if (configured_in_storage()) {
|
||||||
// already converted or set by the user
|
// already converted or set by the user
|
||||||
|
@ -2143,10 +2143,46 @@ bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor
|
||||||
|
|
||||||
AP_Param *old_ap = (AP_Param *)&old_value[0];
|
AP_Param *old_ap = (AP_Param *)&old_value[0];
|
||||||
|
|
||||||
// going via float is safe as the only time we would be converting
|
if (!bitmask) {
|
||||||
// from AP_Int32 is when converting to float
|
// Numeric conversion
|
||||||
float old_float_value = old_ap->cast_to_float(old_ptype);
|
// going via float is safe as the only time we would be converting
|
||||||
set_value(new_ptype, this, old_float_value*scale_factor);
|
// from AP_Int32 is when converting to float
|
||||||
|
float old_float_value = old_ap->cast_to_float(old_ptype);
|
||||||
|
set_value(new_ptype, this, old_float_value*scale_factor);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// Bitmask conversion, go via uint32
|
||||||
|
// int8 -1 should convert to int16 255
|
||||||
|
uint32_t mask;
|
||||||
|
switch (old_ptype) {
|
||||||
|
case AP_PARAM_INT8:
|
||||||
|
mask = (uint8_t)(*(AP_Int8*)old_ap);
|
||||||
|
break;
|
||||||
|
case AP_PARAM_INT16:
|
||||||
|
mask = (uint16_t)(*(AP_Int16*)old_ap);
|
||||||
|
break;
|
||||||
|
case AP_PARAM_INT32:
|
||||||
|
mask = (uint32_t)(*(AP_Int32*)old_ap);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (new_ptype) {
|
||||||
|
case AP_PARAM_INT8:
|
||||||
|
((AP_Int8 *)this)->set(mask);
|
||||||
|
break;
|
||||||
|
case AP_PARAM_INT16:
|
||||||
|
((AP_Int16 *)this)->set(mask);
|
||||||
|
break;
|
||||||
|
case AP_PARAM_INT32:
|
||||||
|
((AP_Int32 *)this)->set(mask);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// force save as the new type
|
// force save as the new type
|
||||||
save(true);
|
save(true);
|
||||||
|
|
|
@ -495,11 +495,17 @@ public:
|
||||||
values without changing the parameter indexes. This will return
|
values without changing the parameter indexes. This will return
|
||||||
true if the parameter was converted from an old parameter value
|
true if the parameter was converted from an old parameter value
|
||||||
*/
|
*/
|
||||||
bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0);
|
bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0) {
|
||||||
|
return _convert_parameter_width(old_ptype, scale_factor, false);
|
||||||
|
}
|
||||||
bool convert_centi_parameter(ap_var_type old_ptype) {
|
bool convert_centi_parameter(ap_var_type old_ptype) {
|
||||||
return convert_parameter_width(old_ptype, 0.01f);
|
return convert_parameter_width(old_ptype, 0.01f);
|
||||||
}
|
}
|
||||||
|
// Converting bitmasks should be done bitwise rather than numerically
|
||||||
|
bool convert_bitmask_parameter_width(ap_var_type old_ptype) {
|
||||||
|
return _convert_parameter_width(old_ptype, 1.0, true);
|
||||||
|
}
|
||||||
|
|
||||||
// convert a single parameter with scaling
|
// convert a single parameter with scaling
|
||||||
enum {
|
enum {
|
||||||
CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion
|
CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion
|
||||||
|
@ -785,6 +791,13 @@ private:
|
||||||
// return true if the parameter is configured in EEPROM/FRAM
|
// return true if the parameter is configured in EEPROM/FRAM
|
||||||
bool configured_in_storage(void) const;
|
bool configured_in_storage(void) const;
|
||||||
|
|
||||||
|
/*
|
||||||
|
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, float scale_factor, bool bitmask);
|
||||||
|
|
||||||
// send a parameter to all GCS instances
|
// send a parameter to all GCS instances
|
||||||
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
|
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue