mirror of https://github.com/ArduPilot/ardupilot
AP_Progmem: added pgm_read_block()
This commit is contained in:
parent
d57fcf7e46
commit
abfb601db6
|
@ -56,6 +56,12 @@ static inline char *strncpy_P(char *buffer, const prog_char_t *pstr, size_t buff
|
|||
return strncpy_P(buffer, (const prog_char *)pstr, buffer_size);
|
||||
}
|
||||
|
||||
static inline void pgm_read_block(const void *s, void *dest, uint8_t len) {
|
||||
uint8_t *dp = (uint8_t *)dest;
|
||||
for (uint8_t i=0; i<len; i++) {
|
||||
dp[i] = pgm_read_byte(i + (const prog_char *)s);
|
||||
}
|
||||
}
|
||||
|
||||
// read something the size of a pointer. This makes the menu code more
|
||||
// portable
|
||||
|
@ -64,15 +70,9 @@ static inline uintptr_t pgm_read_pointer(const void *s)
|
|||
if (sizeof(uintptr_t) == sizeof(uint16_t)) {
|
||||
return (uintptr_t)pgm_read_word(s);
|
||||
} else {
|
||||
union {
|
||||
uintptr_t p;
|
||||
uint8_t a[sizeof(uintptr_t)];
|
||||
} u;
|
||||
uint8_t i;
|
||||
for (i=0; i< sizeof(uintptr_t); i++) {
|
||||
u.a[i] = pgm_read_byte(i + (const prog_char *)s);
|
||||
}
|
||||
return u.p;
|
||||
uintptr_t p;
|
||||
pgm_read_block(s, &p, sizeof(p));
|
||||
return p;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -80,5 +80,11 @@ static inline uintptr_t pgm_read_pointer(const void *s) {
|
|||
return *(const uintptr_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a pointer. This makes the menu code more
|
||||
// portable
|
||||
static inline void pgm_read_block(const void *s, void *dest, uint8_t len) {
|
||||
memcpy(dest, s, len);
|
||||
}
|
||||
|
||||
#endif // __AP_PROGMEM_IDENTITY__
|
||||
|
||||
|
|
Loading…
Reference in New Issue