From 65e719ccc3784d6cbfdd755155d8c4ef6771ba93 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Sun, 25 Oct 2015 17:01:02 -0200 Subject: [PATCH] AP_Param: replace find_P() with find() --- libraries/AP_Param/AP_Param.cpp | 13 +------------ libraries/AP_Param/AP_Param.h | 1 - 2 files changed, 1 insertion(+), 13 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 10a00634ce..f16ae3d102 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -642,17 +642,6 @@ AP_Param::find_def_value_ptr(const char *name) return &info->def_value; } -// Find a variable by name. -// -AP_Param * -AP_Param::find_P(const prog_char_t *name, enum ap_var_type *ptype) -{ - char param_name[AP_MAX_NAME_SIZE+1]; - strncpy(param_name, name, AP_MAX_NAME_SIZE); - param_name[AP_MAX_NAME_SIZE] = 0; - return find(param_name, ptype); -} - // Find a variable by index. Note that this is quite slow. // AP_Param * @@ -1214,7 +1203,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info) // find the new variable in the variable structures enum ap_var_type ptype; AP_Param *ap2; - ap2 = find_P((const prog_char_t *)&info->new_name[0], &ptype); + ap2 = find(&info->new_name[0], &ptype); if (ap2 == NULL) { hal.console->printf_P("Unknown conversion '%s'\n", info->new_name); return; diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 065fa78e8d..82de0f2465 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -152,7 +152,6 @@ public: /// it does not exist. /// static AP_Param * find(const char *name, enum ap_var_type *ptype); - static AP_Param * find_P(const prog_char_t *name, enum ap_var_type *ptype); /// Find a variable by index. ///