mirror of https://github.com/ArduPilot/ardupilot
Replace use of strcpy_P() with strcpy()
This commit is contained in:
parent
e4b313d2ca
commit
1336d621be
|
@ -274,11 +274,11 @@ void AP_AutoTune::log_param_change(float v, const prog_char_t *suffix)
|
||||||
}
|
}
|
||||||
char key[AP_MAX_NAME_SIZE+1];
|
char key[AP_MAX_NAME_SIZE+1];
|
||||||
if (type == AUTOTUNE_ROLL) {
|
if (type == AUTOTUNE_ROLL) {
|
||||||
strncpy_P(key, "RLL2SRV_", 8);
|
strncpy(key, "RLL2SRV_", 8);
|
||||||
strncpy_P(&key[8], suffix, AP_MAX_NAME_SIZE-8);
|
strncpy(&key[8], suffix, AP_MAX_NAME_SIZE-8);
|
||||||
} else {
|
} else {
|
||||||
strncpy_P(key, "PTCH2SRV_", 9);
|
strncpy(key, "PTCH2SRV_", 9);
|
||||||
strncpy_P(&key[9], suffix, AP_MAX_NAME_SIZE-9);
|
strncpy(&key[9], suffix, AP_MAX_NAME_SIZE-9);
|
||||||
}
|
}
|
||||||
key[AP_MAX_NAME_SIZE] = 0;
|
key[AP_MAX_NAME_SIZE] = 0;
|
||||||
dataflash.Log_Write_Parameter(key, v);
|
dataflash.Log_Write_Parameter(key, v);
|
||||||
|
|
|
@ -528,11 +528,11 @@ void AP_Param::copy_name_token(const ParamToken &token, char *buffer, size_t buf
|
||||||
Debug("no info found");
|
Debug("no info found");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
strncpy_P(buffer, info->name, buffer_size);
|
strncpy(buffer, info->name, buffer_size);
|
||||||
if (ginfo != NULL) {
|
if (ginfo != NULL) {
|
||||||
uint8_t len = strnlen(buffer, buffer_size);
|
uint8_t len = strnlen(buffer, buffer_size);
|
||||||
if (len < buffer_size) {
|
if (len < buffer_size) {
|
||||||
strncpy_P(&buffer[len], ginfo->name, buffer_size-len);
|
strncpy(&buffer[len], ginfo->name, buffer_size-len);
|
||||||
}
|
}
|
||||||
if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == PGM_UINT8(&ginfo->type)) {
|
if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == PGM_UINT8(&ginfo->type)) {
|
||||||
// the caller wants a specific element in a Vector3f
|
// the caller wants a specific element in a Vector3f
|
||||||
|
@ -648,7 +648,7 @@ AP_Param *
|
||||||
AP_Param::find_P(const prog_char_t *name, enum ap_var_type *ptype)
|
AP_Param::find_P(const prog_char_t *name, enum ap_var_type *ptype)
|
||||||
{
|
{
|
||||||
char param_name[AP_MAX_NAME_SIZE+1];
|
char param_name[AP_MAX_NAME_SIZE+1];
|
||||||
strncpy_P(param_name, name, AP_MAX_NAME_SIZE);
|
strncpy(param_name, name, AP_MAX_NAME_SIZE);
|
||||||
param_name[AP_MAX_NAME_SIZE] = 0;
|
param_name[AP_MAX_NAME_SIZE] = 0;
|
||||||
return find(param_name, ptype);
|
return find(param_name, ptype);
|
||||||
}
|
}
|
||||||
|
|
|
@ -646,9 +646,9 @@ void DataFlash_Backend::Log_Fill_Format(const struct LogStructure *s, struct log
|
||||||
pkt.msgid = LOG_FORMAT_MSG;
|
pkt.msgid = LOG_FORMAT_MSG;
|
||||||
pkt.type = PGM_UINT8(&s->msg_type);
|
pkt.type = PGM_UINT8(&s->msg_type);
|
||||||
pkt.length = PGM_UINT8(&s->msg_len);
|
pkt.length = PGM_UINT8(&s->msg_len);
|
||||||
strncpy_P(pkt.name, s->name, sizeof(pkt.name));
|
strncpy(pkt.name, s->name, sizeof(pkt.name));
|
||||||
strncpy_P(pkt.format, s->format, sizeof(pkt.format));
|
strncpy(pkt.format, s->format, sizeof(pkt.format));
|
||||||
strncpy_P(pkt.labels, s->labels, sizeof(pkt.labels));
|
strncpy(pkt.labels, s->labels, sizeof(pkt.labels));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1068,7 +1068,7 @@ bool DataFlash_Class::Log_Write_Message_P(const prog_char_t *message)
|
||||||
time_us : hal.scheduler->micros64(),
|
time_us : hal.scheduler->micros64(),
|
||||||
msg : {}
|
msg : {}
|
||||||
};
|
};
|
||||||
strncpy_P(pkt.msg, message, sizeof(pkt.msg));
|
strncpy(pkt.msg, message, sizeof(pkt.msg));
|
||||||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue