AP_Param: print length of defaults list as part of key dump

This commit is contained in:
Iampete1 2023-01-03 01:29:29 +00:00 committed by Andrew Tridgell
parent f90990b3a2
commit 6cd5cf8195
1 changed files with 10 additions and 0 deletions

View File

@ -2793,6 +2793,16 @@ void AP_Param::show_all(AP_HAL::BetterStream *port, bool showKeyValues)
show(ap, token, type, port);
hal.scheduler->delay(1);
}
#if AP_PARAM_DEFAULTS_ENABLED
uint16_t list_len = 0;
if (default_list != nullptr) {
for (defaults_list *item = default_list; item; item = item->next) {
list_len++;
}
}
::printf("Defaults list containts %i params (%li bytes)\n", list_len, list_len*sizeof(defaults_list));
#endif
}
#endif // AP_PARAM_KEY_DUMP