forked from Archive/PX4-Autopilot
param: add 'param show-for-airframe' command
- simplifies creation of an airframe config - could be done from QGC, but it only knows if a param is non-default from metadata, which can be incorrect/missing information - for the list of exceptions we could look at '@category', but we don't have that info in the build - there might be some more exceptions to be added
This commit is contained in:
parent
458420f9cb
commit
f106e6b266
|
@ -85,10 +85,12 @@ static int do_save_default();
|
|||
static int do_load(const char *param_file_name);
|
||||
static int do_import(const char *param_file_name);
|
||||
static int do_show(const char *search_string, bool only_changed);
|
||||
static int do_show_for_airframe();
|
||||
static int do_show_all();
|
||||
static int do_show_quiet(const char *param_name);
|
||||
static int do_show_index(const char *index, bool used_index);
|
||||
static void do_show_print(void *arg, param_t param);
|
||||
static void do_show_print_for_airframe(void *arg, param_t param);
|
||||
static int do_set(const char *name, const char *val, bool fail_on_not_found);
|
||||
static int do_compare(const char *name, char *vals[], unsigned comparisons, enum COMPARE_OPERATOR cmd_op,
|
||||
enum COMPARE_ERROR_LEVEL err_level);
|
||||
|
@ -141,6 +143,8 @@ $ reboot
|
|||
PRINT_MODULE_USAGE_PARAM_FLAG('q', "quiet mode, print only param value (name needs to be exact)", true);
|
||||
PRINT_MODULE_USAGE_ARG("<filter>", "Filter by param name (wildcard at end allowed, eg. sys_*)", true);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("show-for-airframe", "Show changed params for airframe config");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print status of parameter system");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("set", "Set parameter to a value");
|
||||
|
@ -255,6 +259,10 @@ param_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "show-for-airframe")) {
|
||||
return do_show_for_airframe();
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
param_print_status();
|
||||
return PX4_OK;
|
||||
|
@ -464,6 +472,16 @@ do_show(const char *search_string, bool only_changed)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
do_show_for_airframe()
|
||||
{
|
||||
PARAM_PRINT("if [ $AUTOCNF = yes ]\n");
|
||||
PARAM_PRINT("then\n");
|
||||
param_foreach(do_show_print_for_airframe, nullptr, true, true);
|
||||
PARAM_PRINT("fi\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
do_show_all()
|
||||
{
|
||||
|
@ -578,7 +596,7 @@ do_show_print(void *arg, param_t param)
|
|||
const char *p_name = (const char *)param_name(param);
|
||||
|
||||
/* print nothing if search string is invalid and not matching */
|
||||
if (!(arg == nullptr)) {
|
||||
if (arg != nullptr) {
|
||||
|
||||
/* start search */
|
||||
const char *ss = search_string;
|
||||
|
@ -646,6 +664,49 @@ do_show_print(void *arg, param_t param)
|
|||
PARAM_PRINT("<error fetching parameter %lu>\n", (unsigned long)param);
|
||||
}
|
||||
|
||||
static void
|
||||
do_show_print_for_airframe(void *arg, param_t param)
|
||||
{
|
||||
// exceptions
|
||||
const char* p_name = param_name(param);
|
||||
if (!p_name || param_is_volatile(param)) {
|
||||
return;
|
||||
}
|
||||
if (!strcmp(p_name, "SYS_AUTOSTART") || !strcmp(p_name, "SYS_AUTOCONFIG")) {
|
||||
return;
|
||||
}
|
||||
if (!strncmp(p_name, "RC", 2) || !strncmp(p_name, "TC_", 3) || !strncmp(p_name, "CAL_", 4) ||
|
||||
!strncmp(p_name, "SENS_BOARD_", 11) || !strcmp(p_name, "SENS_DPRES_OFF") ||
|
||||
!strcmp(p_name, "MAV_TYPE")) {
|
||||
return;
|
||||
}
|
||||
|
||||
int32_t i;
|
||||
float f;
|
||||
PARAM_PRINT("\tparam set %s ", p_name);
|
||||
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
if (!param_get(param, &i)) {
|
||||
PARAM_PRINT("%ld\n", (long)i);
|
||||
return;
|
||||
}
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
if (!param_get(param, &f)) {
|
||||
PARAM_PRINT("%4.4f\n", (double)f);
|
||||
return;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
PARAM_PRINT("<error fetching parameter %lu>\n", (unsigned long)param);
|
||||
}
|
||||
|
||||
static int
|
||||
do_set(const char *name, const char *val, bool fail_on_not_found)
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue