AP_Param: added generic cast_to_float

This commit is contained in:
Andrew Tridgell 2012-02-12 19:18:58 +11:00
parent a1057fe738
commit 34bc88eab5
2 changed files with 21 additions and 0 deletions

View File

@ -650,3 +650,21 @@ AP_Param *AP_Param::next_scalar(uint32_t *token, enum ap_var_type *ptype)
} }
return ap; return ap;
} }
/// cast a variable to a float given its type
float AP_Param::cast_to_float(enum ap_var_type type)
{
switch (type) {
case AP_PARAM_INT8:
return ((AP_Int8 *)this)->cast_to_float();
case AP_PARAM_INT16:
return ((AP_Int16 *)this)->cast_to_float();
case AP_PARAM_INT32:
return ((AP_Int32 *)this)->cast_to_float();
case AP_PARAM_FLOAT:
return ((AP_Float *)this)->cast_to_float();
default:
return NAN;
}
}

View File

@ -143,6 +143,9 @@ public:
/// as needed /// as needed
static AP_Param *next_scalar(uint32_t *token, enum ap_var_type *ptype); static AP_Param *next_scalar(uint32_t *token, enum ap_var_type *ptype);
/// cast a variable to a float given its type
float cast_to_float(enum ap_var_type type);
private: private:
/// EEPROM header /// EEPROM header
/// ///