mirror of https://github.com/ArduPilot/ardupilot
added AP_Param::show_all()
this moves the logic into common code
This commit is contained in:
parent
781617cae0
commit
16a5b5c3ee
|
@ -102,34 +102,8 @@ setup_show(uint8_t argc, const Menu::arg *argv)
|
|||
report_gyro();
|
||||
#endif
|
||||
|
||||
uint16_t token;
|
||||
AP_Param *ap;
|
||||
enum ap_var_type type;
|
||||
AP_Param::show_all();
|
||||
|
||||
for (ap=AP_Param::first(&token, &type);
|
||||
ap;
|
||||
ap=AP_Param::next_scalar(&token, &type)) {
|
||||
char s[AP_MAX_NAME_SIZE+1];
|
||||
ap->copy_name(s, sizeof(s));
|
||||
s[AP_MAX_NAME_SIZE] = 0;
|
||||
|
||||
switch (type) {
|
||||
case AP_PARAM_INT8:
|
||||
Serial.printf_P("%s: %d\n", s, (int)((AP_Int8 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_INT16:
|
||||
Serial.printf_P("%s: %d\n", s, (int)((AP_Int16 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_INT32:
|
||||
Serial.printf_P("%s: %ld\n", s, (long)((AP_Int32 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_FLOAT:
|
||||
Serial.printf_P("%s: %f\n", s, ((AP_Float *)ap)->get());
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -66,34 +66,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
|
|||
Serial.printf_P(PSTR("Raw Values\n"));
|
||||
print_divider();
|
||||
|
||||
uint16_t token;
|
||||
AP_Param *ap;
|
||||
enum ap_var_type type;
|
||||
|
||||
for (ap=AP_Param::first(&token, &type);
|
||||
ap;
|
||||
ap=AP_Param::next_scalar(&token, &type)) {
|
||||
char s[AP_MAX_NAME_SIZE+1];
|
||||
ap->copy_name(s, sizeof(s));
|
||||
s[AP_MAX_NAME_SIZE] = 0;
|
||||
|
||||
switch (type) {
|
||||
case AP_PARAM_INT8:
|
||||
Serial.printf_P("%s: %d\n", s, (int)((AP_Int8 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_INT16:
|
||||
Serial.printf_P("%s: %d\n", s, (int)((AP_Int16 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_INT32:
|
||||
Serial.printf_P("%s: %ld\n", s, (long)((AP_Int32 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_FLOAT:
|
||||
Serial.printf_P("%s: %f\n", s, ((AP_Float *)ap)->get());
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
AP_Param::show_all();
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
|
|
@ -102,6 +102,9 @@ void setup() {
|
|||
ap=AP_Param::next(&token, &type)) {
|
||||
test_variable(ap, type);
|
||||
}
|
||||
|
||||
AP_Param::show_all();
|
||||
|
||||
Serial.println_P(PSTR("All done."));
|
||||
}
|
||||
|
||||
|
|
|
@ -684,3 +684,37 @@ float AP_Param::cast_to_float(enum ap_var_type type)
|
|||
return NAN;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// print the value of all variables
|
||||
void AP_Param::show_all(void)
|
||||
{
|
||||
uint16_t token;
|
||||
AP_Param *ap;
|
||||
enum ap_var_type type;
|
||||
|
||||
for (ap=AP_Param::first(&token, &type);
|
||||
ap;
|
||||
ap=AP_Param::next_scalar(&token, &type)) {
|
||||
char s[AP_MAX_NAME_SIZE+1];
|
||||
ap->copy_name(s, sizeof(s));
|
||||
s[AP_MAX_NAME_SIZE] = 0;
|
||||
|
||||
switch (type) {
|
||||
case AP_PARAM_INT8:
|
||||
Serial.printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int8 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_INT16:
|
||||
Serial.printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int16 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_INT32:
|
||||
Serial.printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get());
|
||||
break;
|
||||
case AP_PARAM_FLOAT:
|
||||
Serial.printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get());
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -128,6 +128,9 @@ public:
|
|||
///
|
||||
static void erase_all(void);
|
||||
|
||||
/// print the value of all variables
|
||||
static void show_all(void);
|
||||
|
||||
/// Returns the first variable
|
||||
///
|
||||
/// @return The first variable in _var_info, or NULL if
|
||||
|
|
Loading…
Reference in New Issue