mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: add return to strncpy_noterm
This commit is contained in:
parent
c386f9bdcd
commit
ac905caae9
@ -74,14 +74,16 @@ bool hex_to_uint8(uint8_t a, uint8_t &res)
|
|||||||
/*
|
/*
|
||||||
strncpy without the warning for not leaving room for nul termination
|
strncpy without the warning for not leaving room for nul termination
|
||||||
*/
|
*/
|
||||||
void strncpy_noterm(char *dest, const char *src, size_t n)
|
size_t strncpy_noterm(char *dest, const char *src, size_t n)
|
||||||
{
|
{
|
||||||
size_t len = strnlen(src, n);
|
size_t len = strnlen(src, n);
|
||||||
|
size_t ret = len; // return value is length of src
|
||||||
if (len < n) {
|
if (len < n) {
|
||||||
// include nul term if it fits
|
// include nul term if it fits
|
||||||
len++;
|
len++;
|
||||||
}
|
}
|
||||||
memcpy(dest, src, len);
|
memcpy(dest, src, len);
|
||||||
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -158,7 +158,7 @@ bool hex_to_uint8(uint8_t a, uint8_t &res); // return the uint8 value of an asc
|
|||||||
/*
|
/*
|
||||||
strncpy without the warning for not leaving room for nul termination
|
strncpy without the warning for not leaving room for nul termination
|
||||||
*/
|
*/
|
||||||
void strncpy_noterm(char *dest, const char *src, size_t n);
|
size_t strncpy_noterm(char *dest, const char *src, size_t n);
|
||||||
|
|
||||||
// return the numeric value of an ascii hex character
|
// return the numeric value of an ascii hex character
|
||||||
int16_t char_to_hex(char a);
|
int16_t char_to_hex(char a);
|
||||||
|
Loading…
Reference in New Issue
Block a user