AP_Param: add and use global NaNf float value

This commit is contained in:
Peter Barker 2024-09-23 19:43:12 +10:00 committed by Peter Barker
parent edc0e46614
commit 06b763ca94
1 changed files with 2 additions and 2 deletions

View File

@ -2945,14 +2945,14 @@ void AP_Param::show_all(AP_HAL::BetterStream *port, bool showKeyValues)
ParamToken token; ParamToken token;
AP_Param *ap; AP_Param *ap;
enum ap_var_type type; enum ap_var_type type;
float default_value = nanf("0x4152"); // from logger quiet_nanf float default_value = NaNf; // from logger quiet_nanf
for (ap=AP_Param::first(&token, &type, &default_value); for (ap=AP_Param::first(&token, &type, &default_value);
ap; ap;
ap=AP_Param::next_scalar(&token, &type, &default_value)) { ap=AP_Param::next_scalar(&token, &type, &default_value)) {
if (showKeyValues) { if (showKeyValues) {
::printf("Key %u: Index %u: GroupElement %u : Default %f :", (unsigned)var_info(token.key).key, (unsigned)token.idx, (unsigned)token.group_element, default_value); ::printf("Key %u: Index %u: GroupElement %u : Default %f :", (unsigned)var_info(token.key).key, (unsigned)token.idx, (unsigned)token.group_element, default_value);
default_value = nanf("0x4152"); default_value = NaNf;
} }
show(ap, token, type, port); show(ap, token, type, port);
hal.scheduler->delay(1); hal.scheduler->delay(1);