mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: fixed PSTR() usage
This commit is contained in:
parent
089e63f987
commit
88fb7ddff8
@ -1154,7 +1154,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info)
|
||||
AP_Param *ap2;
|
||||
ap2 = find_P((const prog_char_t *)&info->new_name[0], &ptype);
|
||||
if (ap2 == NULL) {
|
||||
hal.console->printf_P("Unknown conversion '%s'\n", info->new_name);
|
||||
hal.console->printf_P(PSTR("Unknown conversion '%s'\n"), info->new_name);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -1184,7 +1184,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info)
|
||||
}
|
||||
} else {
|
||||
// can't do vector<->scalar conversion, or different vector types
|
||||
hal.console->printf_P("Bad conversion type '%s'\n", info->new_name);
|
||||
hal.console->printf_P(PSTR("Bad conversion type '%s'\n"), info->new_name);
|
||||
}
|
||||
}
|
||||
#pragma GCC diagnostic pop
|
||||
|
Loading…
Reference in New Issue
Block a user