Classes | Macros
utils.h File Reference
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/delay.h>
Include dependency graph for utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  long_to_byte_t
 

Macros

#define FALSE   (1!=1)
 
#define NULL   ((void*)0)
 Nullzeiger. More...
 
#define TRUE   (1==1)
 
Nützliches
#define DEGREE_TO_RAD(x)   ((x * M_PI) / 180)
 
#define HIGH_BYTE(x)   ((uint8_t) (x >> 8))
 
#define HIGH_WORD(x)   ((uint16_t) (x >> 16))
 
#define LOW_BYTE(x)   ((uint8_t) (x & 0xff))
 
#define LOW_WORD(x)   ((uint16_t) (x & 0xffff))
 
Volatile Zugriff auf Variablen
#define vs16(x)   (*(volatile int16_t*)&(x))
 
#define vs32(x)   (*(volatile int32_t*)&(x))
 
#define vs8(x)   (*(volatile int8_t*)&(x))
 
#define vu16(x)   (*(volatile uint16_t*)&(x))
 
#define vu32(x)   (*(volatile uint32_t*)&(x))
 
#define vu8(x)   (*(volatile uint8_t*)&(x))
 
Port-Makros

Die Makros RESET(), SET(), SET_OUTPUT(), SET_INPUT() und IS_SET() beziehen sich immer auf ein bestimmtes Bit eines Ports und helfen somit den Code sehr portabel zu gestalten.

Beispiel:

#define LED D,5 // PORTD, Pin 5
SET_OUTPUT(LED); // Pin als Ausgang schalten (wird z.B. zu DDRD |= (1<<5);)
SET(LED); // LED aktivieren

oder auch:

#define SCHALTER B,1 // PORTB, Pin 1
if (IS_SET(SCHALTER)) {
...
}

Somit muss nur ein Define geändert werden sobald ein anderer Pin verwendet werden soll. Außerdem muss nicht immer noch ein extra Define für den entsprechenden Port angelegt werden wie es bisher immer der Fall war.

#define _ddr2(x)   DDR ## x
 
#define _pin2(x)   PIN ## x
 
#define _pin_num(x, y)   y
 
#define _port2(x)   PORT ## x
 
#define _reg(x, y)   x
 
#define DDR(x)   _ddr2(x)
 
#define IS_SET(x)   IS_SET2(x)
 
#define IS_SET2(x, y)   ((PIN(x) & (1<<y)) != 0)
 
#define PIN(x)   _pin2(x)
 
#define PIN_NUM(x)   _pin_num(x)
 
#define PORT(x)   _port2(x)
 
#define REG(x)   _reg(x)
 
#define RESET(x)   RESET2(x)
 
#define RESET2(x, y)   PORT(x) &= ~(1<<y)
 
#define SET(x)   SET2(x)
 
#define SET2(x, y)   PORT(x) |= (1<<y)
 
#define SET_INPUT(x)   SET_INPUT2(x)
 
#define SET_INPUT2(x, y)   DDR(x) &= ~(1<<y)
 
#define SET_INPUT_WITH_PULLUP(x)   SET_INPUT_WITH_PULLUP2(x)
 
#define SET_INPUT_WITH_PULLUP2(x, y)   SET_INPUT2(x,y);SET2(x,y)
 
#define SET_OUTPUT(x)   SET_OUTPUT2(x)
 
#define SET_OUTPUT2(x, y)   DDR(x) |= (1<<y)
 
#define SET_PULLUP(x)   SET2(x)
 
#define TOGGLE(x)   TOGGLE2(x)
 
#define TOGGLE2(x, y)   PORT(x) ^= (1<<y)
 

Kritische Sektionen (Interrupts sperren)

#define ENTER_CRITICAL_SECTION   do { unsigned char sreg_ = SREG; cli();
 
#define LEAVE_CRITICAL_SECTION   SREG = sreg_; } while (0);
 
static uint8_t read_and_replace_atomar (volatile uint8_t *data, uint8_t new_data)
 atomare Operationen More...
 

weitere nuetzliche Makros

#define _bit_is_clear(pin, bit)   (!(pin & (1<<bit)))
 
#define _bit_is_set(pin, bit)   (pin & (1<<bit))
 
#define _STRING(x)   #x
 
static uint8_t bit_count32 (uint32_t n)
 Zählt die Anzahl der gesetzten Bits in einem Byte. More...
 
static uint8_t bit_count8 (uint8_t n)
 Zählt die Anzahl der gesetzten Bits in einem Byte. More...
 
#define DEBUG_PRINT(s, ...)
 
More...
 
#define END_TIMED_BLOCK
 
#define MASK_00001111   (((uint32_t)(-1))/17)
 
#define MASK_00110011   (((uint32_t)(-1))/5)
 
#define MASK_01010101   (((uint32_t)(-1))/3)
 
#define START_TIMED_BLOCK(time, gettime)
 
#define STRING(x)   _STRING(x)
 
static uint8_t swap (uint8_t x)
 Dreht die beiden Nibble in einem Byte um. More...
 
#define TO_DEG(x)   (x * 180.0 / M_PI)
 
#define TO_RAD(x)   (x * M_PI / 180.0)
 
#define USE_IT(x)   (void) x
 Macro to supress "unused argument" warnings from the compiler. More...
 

Macro Definition Documentation

◆ _bit_is_clear

#define _bit_is_clear (   pin,
  bit 
)    (!(pin & (1<<bit)))

Definition at line 274 of file utils.h.

◆ _bit_is_set

#define _bit_is_set (   pin,
  bit 
)    (pin & (1<<bit))

Definition at line 273 of file utils.h.

◆ _ddr2

#define _ddr2 (   x)    DDR ## x

Definition at line 239 of file utils.h.

◆ _pin2

#define _pin2 (   x)    PIN ## x

Definition at line 240 of file utils.h.

◆ _pin_num

#define _pin_num (   x,
 
)    y

Definition at line 243 of file utils.h.

◆ _port2

#define _port2 (   x)    PORT ## x

Definition at line 238 of file utils.h.

◆ _reg

#define _reg (   x,
 
)    x

Definition at line 242 of file utils.h.

◆ _STRING

#define _STRING (   x)    #x

Definition at line 277 of file utils.h.

◆ DDR

#define DDR (   x)    _ddr2(x)

Definition at line 223 of file utils.h.

◆ DEGREE_TO_RAD

#define DEGREE_TO_RAD (   x)    ((x * M_PI) / 180)

Definition at line 74 of file utils.h.

◆ END_TIMED_BLOCK

#define END_TIMED_BLOCK
Value:
} \
} while (0);

Definition at line 361 of file utils.h.

◆ ENTER_CRITICAL_SECTION

#define ENTER_CRITICAL_SECTION   do { unsigned char sreg_ = SREG; cli();

Definition at line 126 of file utils.h.

◆ FALSE

#define FALSE   (1!=1)

Definition at line 58 of file utils.h.

◆ HIGH_BYTE

#define HIGH_BYTE (   x)    ((uint8_t) (x >> 8))

Definition at line 85 of file utils.h.

◆ HIGH_WORD

#define HIGH_WORD (   x)    ((uint16_t) (x >> 16))

Definition at line 87 of file utils.h.

◆ IS_SET

#define IS_SET (   x)    IS_SET2(x)

Definition at line 234 of file utils.h.

◆ IS_SET2

#define IS_SET2 (   x,
 
)    ((PIN(x) & (1<<y)) != 0)

Definition at line 253 of file utils.h.

◆ LEAVE_CRITICAL_SECTION

#define LEAVE_CRITICAL_SECTION   SREG = sreg_; } while (0);

Definition at line 127 of file utils.h.

◆ LOW_BYTE

#define LOW_BYTE (   x)    ((uint8_t) (x & 0xff))

Definition at line 84 of file utils.h.

◆ LOW_WORD

#define LOW_WORD (   x)    ((uint16_t) (x & 0xffff))

Definition at line 86 of file utils.h.

◆ MASK_00001111

#define MASK_00001111   (((uint32_t)(-1))/17)

Definition at line 334 of file utils.h.

◆ MASK_00110011

#define MASK_00110011   (((uint32_t)(-1))/5)

Definition at line 333 of file utils.h.

◆ MASK_01010101

#define MASK_01010101   (((uint32_t)(-1))/3)

Definition at line 332 of file utils.h.

◆ NULL

#define NULL   ((void*)0)

Nullzeiger.

Definition at line 64 of file utils.h.

◆ PIN

#define PIN (   x)    _pin2(x)

Definition at line 224 of file utils.h.

◆ PIN_NUM

#define PIN_NUM (   x)    _pin_num(x)

Definition at line 226 of file utils.h.

◆ PORT

#define PORT (   x)    _port2(x)

Definition at line 222 of file utils.h.

◆ REG

#define REG (   x)    _reg(x)

Definition at line 225 of file utils.h.

◆ RESET

#define RESET (   x)    RESET2(x)

Definition at line 228 of file utils.h.

◆ RESET2

#define RESET2 (   x,
 
)    PORT(x) &= ~(1<<y)

Definition at line 245 of file utils.h.

◆ SET

#define SET (   x)    SET2(x)

Definition at line 229 of file utils.h.

◆ SET2

#define SET2 (   x,
 
)    PORT(x) |= (1<<y)

Definition at line 246 of file utils.h.

◆ SET_INPUT

#define SET_INPUT (   x)    SET_INPUT2(x)

Definition at line 232 of file utils.h.

◆ SET_INPUT2

#define SET_INPUT2 (   x,
 
)    DDR(x) &= ~(1<<y)

Definition at line 250 of file utils.h.

◆ SET_INPUT_WITH_PULLUP

#define SET_INPUT_WITH_PULLUP (   x)    SET_INPUT_WITH_PULLUP2(x)

Definition at line 236 of file utils.h.

◆ SET_INPUT_WITH_PULLUP2

#define SET_INPUT_WITH_PULLUP2 (   x,
 
)    SET_INPUT2(x,y);SET2(x,y)

Definition at line 251 of file utils.h.

◆ SET_OUTPUT

#define SET_OUTPUT (   x)    SET_OUTPUT2(x)

Definition at line 231 of file utils.h.

◆ SET_OUTPUT2

#define SET_OUTPUT2 (   x,
 
)    DDR(x) |= (1<<y)

Definition at line 249 of file utils.h.

◆ SET_PULLUP

#define SET_PULLUP (   x)    SET2(x)

Definition at line 233 of file utils.h.

◆ START_TIMED_BLOCK

#define START_TIMED_BLOCK (   time,
  gettime 
)
Value:
do { \
static uint16_t last_time__; \
uint16_t current_time__ = gettime; \
if ((uint16_t) (current_time__ - last_time__) > time) { \
last_time__ = current_time__;

Definition at line 354 of file utils.h.

◆ STRING

#define STRING (   x)    _STRING(x)

Definition at line 276 of file utils.h.

◆ TO_DEG

#define TO_DEG (   x)    (x * 180.0 / M_PI)

Definition at line 366 of file utils.h.

◆ TO_RAD

#define TO_RAD (   x)    (x * M_PI / 180.0)

Definition at line 367 of file utils.h.

◆ TOGGLE

#define TOGGLE (   x)    TOGGLE2(x)

Definition at line 230 of file utils.h.

◆ TOGGLE2

#define TOGGLE2 (   x,
 
)    PORT(x) ^= (1<<y)

Definition at line 247 of file utils.h.

◆ TRUE

#define TRUE   (1==1)

Definition at line 52 of file utils.h.

◆ USE_IT

#define USE_IT (   x)    (void) x

Macro to supress "unused argument" warnings from the compiler.

Todo:
attribute((unused)) for the gcc?

Definition at line 374 of file utils.h.

◆ vs16

#define vs16 (   x)    (*(volatile int16_t*)&(x))

Definition at line 163 of file utils.h.

◆ vs32

#define vs32 (   x)    (*(volatile int32_t*)&(x))

Definition at line 165 of file utils.h.

◆ vs8

#define vs8 (   x)    (*(volatile int8_t*)&(x))

Definition at line 161 of file utils.h.

◆ vu16

#define vu16 (   x)    (*(volatile uint16_t*)&(x))

Definition at line 162 of file utils.h.

◆ vu32

#define vu32 (   x)    (*(volatile uint32_t*)&(x))

Definition at line 164 of file utils.h.

◆ vu8

#define vu8 (   x)    (*(volatile uint8_t*)&(x))

Definition at line 160 of file utils.h.

SET
@ SET
Definition: lpc_types.h:62
uavcan::uint16_t
std::uint16_t uint16_t
Definition: std.hpp:25
SET_INPUT_WITH_PULLUP
#define SET_INPUT_WITH_PULLUP(x)
Definition: utils.h:236
SET_OUTPUT
#define SET_OUTPUT(x)
Definition: utils.h:231
IS_SET
#define IS_SET(x)
Definition: utils.h:234


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:03