mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Progmem: remove dead code
The only thing from AP_Progmem that's still used are the pgm_read_* function and there's no support for AVR anymore. So remove the dead code and use a single header to contain that inline functions.
This commit is contained in:
parent
79230bc68d
commit
92016e9229
@ -1,15 +1,41 @@
|
||||
#pragma once
|
||||
|
||||
#ifndef __AP_PROGMEM_H__
|
||||
#define __AP_PROGMEM_H__
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#if defined(__AVR__)
|
||||
#include "AP_Progmem_AVR.h"
|
||||
#else
|
||||
#include "AP_Progmem_Identity.h"
|
||||
#endif
|
||||
// read something the size of a byte
|
||||
static inline uint8_t pgm_read_byte(const void *s) {
|
||||
return *(const uint8_t *)s;
|
||||
}
|
||||
|
||||
#define PROGMEM_STRING(_v, _s) static const char _v[] PROGMEM = _s
|
||||
// read something the size of a byte, far version
|
||||
static inline uint8_t pgm_read_byte_far(const void *s) {
|
||||
return *(const uint8_t *)s;
|
||||
}
|
||||
|
||||
#endif // __AP_PROGMEM_H__
|
||||
// read something the size of a word
|
||||
static inline uint16_t pgm_read_word(const void *s) {
|
||||
return *(const uint16_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a dword
|
||||
static inline uint32_t pgm_read_dword(const void *s) {
|
||||
return *(const uint32_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a float
|
||||
static inline float pgm_read_float(const void *s) {
|
||||
return *(const float *)s;
|
||||
}
|
||||
|
||||
// read something the size of a pointer. This makes the menu code more
|
||||
// portable
|
||||
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);
|
||||
}
|
||||
|
@ -1,29 +0,0 @@
|
||||
|
||||
/* Only build this file for AVR - it exists to provide overrides for
|
||||
* broken avr libc */
|
||||
#ifdef __AVR__
|
||||
|
||||
#include <string.h>
|
||||
#include "AP_Progmem.h"
|
||||
|
||||
// strlcat_P() in AVR libc seems to be broken
|
||||
size_t strlcat_P(char *d, const prog_char_t *s, size_t bufsize)
|
||||
{
|
||||
size_t len1 = strlen(d);
|
||||
size_t len2 = strlen_P(s);
|
||||
size_t ret = len1 + len2;
|
||||
|
||||
if (len1+len2 >= bufsize) {
|
||||
if (bufsize < (len1+1)) {
|
||||
return ret;
|
||||
}
|
||||
len2 = bufsize - (len1+1);
|
||||
}
|
||||
if (len2 > 0) {
|
||||
memcpy_P(d+len1, s, len2);
|
||||
d[len1+len2] = 0;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif // __AVR__
|
@ -1,68 +0,0 @@
|
||||
|
||||
#ifndef __AP_PROGMEM_AVR_H__
|
||||
#define __AP_PROGMEM_AVR_H__
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
// prog_char_t is used as a wrapper type for prog_char, which is
|
||||
// a character stored in flash. By using this wrapper type we can
|
||||
// auto-detect at compile time if a call to a string function is using
|
||||
// a flash-stored string or not
|
||||
typedef struct {
|
||||
char c;
|
||||
} prog_char_t;
|
||||
|
||||
typedef char prog_char;
|
||||
|
||||
#undef PSTR
|
||||
#define PSTR(s) (__extension__({static const prog_char __c[] PROGMEM = (s); \
|
||||
(const prog_char_t *)&__c[0]; }))
|
||||
|
||||
|
||||
static inline int strcasecmp_P(const char *str1, const prog_char_t *pstr)
|
||||
{
|
||||
return strcasecmp_P(str1, (const prog_char *)pstr);
|
||||
}
|
||||
|
||||
static inline int strcmp_P(const char *str1, const prog_char_t *pstr)
|
||||
{
|
||||
return strcmp_P(str1, (const prog_char *)pstr);
|
||||
}
|
||||
|
||||
static inline size_t strlen_P(const prog_char_t *pstr)
|
||||
{
|
||||
return strlen_P((const prog_char *)pstr);
|
||||
}
|
||||
|
||||
static inline void *memcpy_P(void *dest, const prog_char_t *src, size_t n)
|
||||
{
|
||||
return memcpy_P(dest, (const prog_char *)src, n);
|
||||
}
|
||||
|
||||
|
||||
static inline char *strncpy_P(char *buffer, const prog_char_t *pstr, size_t buffer_size)
|
||||
{
|
||||
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
|
||||
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 {
|
||||
uintptr_t p;
|
||||
pgm_read_block(s, &p, sizeof(p));
|
||||
return p;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // __AP_PROGMEM_AVR_H__
|
@ -1,90 +0,0 @@
|
||||
|
||||
#ifndef __AP_PROGMEM_IDENTITY__
|
||||
#define __AP_PROGMEM_IDENTITY__
|
||||
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
|
||||
typedef char prog_char_t;
|
||||
typedef char prog_char;
|
||||
|
||||
#define PSTR(s) s
|
||||
#undef PROGMEM
|
||||
#define PROGMEM __attribute__(())
|
||||
|
||||
static inline int strcasecmp_P(const char *str1, const prog_char_t *pstr)
|
||||
{
|
||||
return strcasecmp(str1, pstr);
|
||||
}
|
||||
|
||||
static inline int strcmp_P(const char *str1, const prog_char_t *pstr)
|
||||
{
|
||||
return strcmp(str1, pstr);
|
||||
}
|
||||
|
||||
static inline size_t strlen_P(const prog_char_t *pstr)
|
||||
{
|
||||
return strlen(pstr);
|
||||
}
|
||||
|
||||
static inline void *memcpy_P(void *dest, const prog_char_t *src, size_t n)
|
||||
{
|
||||
return memcpy(dest, src, n);
|
||||
}
|
||||
|
||||
|
||||
static inline char *strncpy_P(char *buffer, const prog_char_t *pstr, size_t buffer_size)
|
||||
{
|
||||
return strncpy(buffer, pstr, buffer_size);
|
||||
}
|
||||
|
||||
static inline size_t strnlen_P(const prog_char_t *str, size_t size)
|
||||
{
|
||||
return strnlen(str, size);
|
||||
}
|
||||
|
||||
static inline int strncmp_P(const char *str1, const prog_char_t *str2, size_t n)
|
||||
{
|
||||
return strncmp(str1, str2, n);
|
||||
}
|
||||
|
||||
|
||||
// read something the size of a byte
|
||||
static inline uint8_t pgm_read_byte(const void *s) {
|
||||
return *(const uint8_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a byte, far version
|
||||
static inline uint8_t pgm_read_byte_far(const void *s) {
|
||||
return *(const uint8_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a word
|
||||
static inline uint16_t pgm_read_word(const void *s) {
|
||||
return *(const uint16_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a dword
|
||||
static inline uint32_t pgm_read_dword(const void *s) {
|
||||
return *(const uint32_t *)s;
|
||||
}
|
||||
|
||||
// read something the size of a float
|
||||
static inline float pgm_read_float(const void *s) {
|
||||
return *(const float *)s;
|
||||
}
|
||||
|
||||
// read something the size of a pointer. This makes the menu code more
|
||||
// portable
|
||||
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
Block a user