APM:Libraries
compat.h
Go to the documentation of this file.
1 #ifndef COMPAT_H
2 #define COMPAT_H
3 
4 
5 #include "binary.h"
6 #include <inttypes.h>
7 
8 typedef uint8_t byte;
9 
10 #ifndef PSTR
11 #define PSTR(x) (x)
12 #endif
13 #define PROGMEM
14 
15 typedef uint8_t byte;
16 typedef uint8_t boolean;
17 
18 typedef char prog_char;
19 
20 #define INLINE __attribute__ ((always_inline)) inline
21 #define WEAK __attribute__((weak))
22 
23 typedef const char * PGM_P;
24 
25 #undef PSTR
26 
27 #define PSTR(str) (str)
28 
29 #define BYTE_OF(v,n) (((byte *)&(v))[n])
30 
31 #define TO_STRING2(x) #x
32 #define TO_STRING(x) TO_STRING2(x)
33 
34 
35 static inline int max(int a, int b){
36  if(a>b) return a;
37  return b;
38 }
39 
40 static inline float pgm_read_float(const void * v){
41  const float * addr = (const float *)v;
42  return *addr;
43 }
44 
45 static inline uint8_t pgm_read_byte(const void * v){
46  const byte * addr = (const byte *)v;
47  return *addr;
48 }
49 
50 // this can be used on Arduino's world to load an address so limiting to uint16_t cause HardFault
51 static inline uint32_t pgm_read_word(const void * v){
52  const uint32_t * addr = (const uint32_t *)v;
53  return *addr;
54 }
55 
56 
58 #include <AP_HAL_F4Light/GPIO.h>
61 
62 #ifndef NOINLINE
63 #define NOINLINE __attribute__ ((noinline))
64 #endif
65 
66 using namespace F4Light;
67 
68 
69 #include "../osd_ns.h"
70 
72 
73 using namespace OSDns;
74 
75 
76 typedef uint32_t byte_32;
77 typedef int16_t byte_16;
78 
79 extern void max7456_off();
80 extern void max7456_on();
81 
82 static inline void delayMicroseconds(uint16_t us) { hal_delay_microseconds(us); }
83 //static inline void delay(uint16_t ms) { hal_delay(ms); } no calls to delay() allowed
84 
85 #endif
const char * PGM_P
Definition: compat.h:23
static void delayMicroseconds(uint16_t us)
Definition: compat.h:82
char prog_char
Definition: compat.h:18
void max7456_on()
static int max(int a, int b)
Definition: compat.h:35
static uint8_t pgm_read_byte(const void *v)
Definition: compat.h:45
static float pgm_read_float(const void *v)
Definition: compat.h:40
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void hal_delay_microseconds(uint16_t t)
Definition: Scheduler.cpp:1432
uint8_t boolean
Definition: compat.h:16
float v
Definition: Printf.cpp:15
uint8_t byte
Definition: compat.h:8
uint32_t byte_32
Definition: compat.h:76
static uint32_t pgm_read_word(const void *v)
Definition: compat.h:51
void max7456_off()
int16_t byte_16
Definition: compat.h:77