Replace use of strcasecmp_P() with strcasecmp()

This commit is contained in:
Lucas De Marchi 2015-10-25 14:22:16 -02:00 committed by Randy Mackay
parent 84da1f5039
commit 6f0db45b57
5 changed files with 15 additions and 15 deletions

View File

@ -109,10 +109,10 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
// that name as the argument to the command, and set the bit in
// bits accordingly.
//
if (!strcasecmp_P(argv[1].str, "all")) {
if (!strcasecmp(argv[1].str, "all")) {
bits = ~0;
} else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, #_s)) bits |= MASK_LOG_ ## _s
#define TARG(_s) if (!strcasecmp(argv[1].str, #_s)) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST);
TARG(ATTITUDE_MED);
TARG(GPS);
@ -130,7 +130,7 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
#undef TARG
}
if (!strcasecmp_P(argv[0].str, "enable")) {
if (!strcasecmp(argv[0].str, "enable")) {
g.log_bitmask.set_and_save(g.log_bitmask | bits);
}else{
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);

View File

@ -107,10 +107,10 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
// that name as the argument to the command, and set the bit in
// bits accordingly.
//
if (!strcasecmp_P(argv[1].str, "all")) {
if (!strcasecmp(argv[1].str, "all")) {
bits = ~0;
} else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
#define TARG(_s) if (!strcasecmp(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST);
TARG(ATTITUDE_MED);
TARG(GPS);
@ -129,7 +129,7 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
#undef TARG
}
if (!strcasecmp_P(argv[0].str, "enable")) {
if (!strcasecmp(argv[0].str, "enable")) {
g.log_bitmask.set_and_save(g.log_bitmask | bits);
}else{
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);

View File

@ -109,10 +109,10 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
// that name as the argument to the command, and set the bit in
// bits accordingly.
//
if (!strcasecmp_P(argv[1].str, "all")) {
if (!strcasecmp(argv[1].str, "all")) {
bits = 0xFFFFFFFFUL;
} else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
#define TARG(_s) if (!strcasecmp(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST);
TARG(ATTITUDE_MED);
TARG(GPS);
@ -131,7 +131,7 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
#undef TARG
}
if (!strcasecmp_P(argv[0].str, "enable")) {
if (!strcasecmp(argv[0].str, "enable")) {
g.log_bitmask.set_and_save(g.log_bitmask | bits);
}else{
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);

View File

@ -135,7 +135,7 @@ Menu::_run_command(bool prompt_on_enter)
bool cmd_found = false;
// look for a command matching the first word (note that it may be empty)
for (i = 0; i < _entries; i++) {
if (!strcasecmp_P(_argv[0].str, _commands[i].command)) {
if (!strcasecmp(_argv[0].str, _commands[i].command)) {
ret = _call(i, argc);
cmd_found=true;
if (-2 == ret)
@ -146,10 +146,10 @@ Menu::_run_command(bool prompt_on_enter)
// implicit commands
if (i == _entries) {
if (!strcmp(_argv[0].str, "?") || (!strcasecmp_P(_argv[0].str, "help"))) {
if (!strcmp(_argv[0].str, "?") || (!strcasecmp(_argv[0].str, "help"))) {
_help();
cmd_found=true;
} else if (!strcasecmp_P(_argv[0].str, "exit")) {
} else if (!strcasecmp(_argv[0].str, "exit")) {
// exit the menu
return true;
}

View File

@ -560,7 +560,7 @@ AP_Param::find_group(const char *name, uint8_t vindex, const struct GroupInfo *g
}
} else
#endif // AP_NESTED_GROUPS_ENABLED
if (strcasecmp_P(name, group_info[i].name) == 0) {
if (strcasecmp(name, group_info[i].name) == 0) {
uintptr_t p = PGM_POINTER(&_var_info[vindex].ptr);
*ptype = (enum ap_var_type)type;
return (AP_Param *)(p + PGM_POINTER(&group_info[i].offset));
@ -610,7 +610,7 @@ AP_Param::find(const char *name, enum ap_var_type *ptype)
// we continue looking as we want to allow top level
// parameter to have the same prefix name as group
// parameters, for example CAM_P_G
} else if (strcasecmp_P(name, _var_info[i].name) == 0) {
} else if (strcasecmp(name, _var_info[i].name) == 0) {
*ptype = (enum ap_var_type)type;
return (AP_Param *)PGM_POINTER(&_var_info[i].ptr);
}
@ -674,7 +674,7 @@ AP_Param *
AP_Param::find_object(const char *name)
{
for (uint8_t i=0; i<_num_vars; i++) {
if (strcasecmp_P(name, _var_info[i].name) == 0) {
if (strcasecmp(name, _var_info[i].name) == 0) {
return (AP_Param *)PGM_POINTER(&_var_info[i].ptr);
}
}