Smartcar Shield
Runtime.hpp
Go to the documentation of this file.
1 
10 #pragma once
11 #include <stddef.h> // NOLINT(modernize-deprecated-headers)
12 #include <stdint.h> // NOLINT(modernize-deprecated-headers)
13 
14 // Determine if we use an Espressif platform (i.e. an ESP32 or ESP8266 board).
15 // We need this since they are not fully compatible with the Arduino API
16 // and therefore we have to do some extra adaptations.
17 #if defined(ESP32) || defined(ESP8266)
18 #define ESP_BOARD
19 #endif
20 
21 #include "InterruptCallback.hpp"
22 
23 #ifdef ESP_BOARD
24 #if defined(ESP32)
25 #include "esp_attr.h"
26 #define STORED_IN_RAM IRAM_ATTR
27 #else // ESP8266
28 #include "c_types.h"
29 #define STORED_IN_RAM ICACHE_RAM_ATTR
30 #endif
31 #else // Other architectures
32 #define STORED_IN_RAM
33 #endif
34 
35 class Runtime
36 {
37 public:
38  virtual ~Runtime() = default;
39 
45  virtual void setPinDirection(uint8_t pin, uint8_t direction) = 0;
46 
52  virtual void setPinState(uint8_t pin, uint8_t state) = 0;
53 
59  virtual int getPinState(uint8_t pin) = 0;
60 
66  virtual int getAnalogPinState(uint8_t pin) = 0;
67 
73  virtual void setPWM(uint8_t pin, int dutyCycle) = 0;
74 
78  virtual void i2cInit() = 0;
79 
85  virtual void i2cBeginTransmission(uint8_t address) = 0;
86 
92  virtual size_t i2cWrite(uint8_t value) = 0;
93 
99  virtual uint8_t i2cEndTransmission() = 0;
100 
108  virtual uint8_t i2cRequestFrom(uint8_t address, uint8_t numberOfBytes) = 0;
109 
115  virtual int i2cAvailable() = 0;
116 
121  virtual int i2cRead() = 0;
122 
129  virtual int8_t pinToInterrupt(uint8_t pin) = 0;
130 
136  virtual unsigned long currentTimeMillis() = 0;
137 
143  virtual unsigned long currentTimeMicros() = 0;
144 
150  virtual void delayMillis(unsigned long milliseconds) = 0;
151 
157  virtual void delayMicros(unsigned int microseconds) = 0;
158 
168  virtual unsigned long getPulseDuration(uint8_t pin, uint8_t state, unsigned long timeout) = 0;
169 
177  virtual void setInterrupt(uint8_t pin, InterruptCallback callback, int mode) = 0;
178 
184  virtual uint8_t getLowState() const = 0;
185 
191  virtual uint8_t getHighState() const = 0;
192 
198  virtual uint8_t getOutputState() const = 0;
199 
205  virtual uint8_t getInputState() const = 0;
206 
212  virtual int getRisingEdgeMode() const = 0;
213 };
Runtime::getPinState
virtual int getPinState(uint8_t pin)=0
Get the pin state, equivalent of digitalRead in Arduino.
InterruptCallback.hpp
Runtime::i2cEndTransmission
virtual uint8_t i2cEndTransmission()=0
Ends a transmission to an I2C device equivalent of Wire.endTransmission in Arduino.
Runtime::delayMicros
virtual void delayMicros(unsigned int microseconds)=0
Block the execution for the specified number of microseconds, equivalent of delayMicroseconds in Ardu...
InterruptCallback
A callback to be invoked. Depending on the platform different callback types may be necessary.
Runtime::getHighState
virtual uint8_t getHighState() const =0
Get the runtime-specific value representing a logical HIGH voltage state.
Runtime::i2cInit
virtual void i2cInit()=0
Initialize I2C bus as master, equivalent of Wire.begin in Arduino.
Runtime::setPinState
virtual void setPinState(uint8_t pin, uint8_t state)=0
Set pin state, equivalent of digitalWrite in Arduino.
Runtime::delayMillis
virtual void delayMillis(unsigned long milliseconds)=0
Block the execution for the specified number of milliseconds, equivalent of delay in Arduino.
Runtime::getOutputState
virtual uint8_t getOutputState() const =0
Get the runtime-specific value representing an OUTPUT pin state.
Runtime
Definition: Runtime.hpp:35
Runtime::getRisingEdgeMode
virtual int getRisingEdgeMode() const =0
Get the rising edge constant for setting an interrupt.
Runtime::setInterrupt
virtual void setInterrupt(uint8_t pin, InterruptCallback callback, int mode)=0
Enables an external hardware interrupt and provides a callback, equivalent to attachInterrupt in Ardu...
Runtime::i2cBeginTransmission
virtual void i2cBeginTransmission(uint8_t address)=0
Initiate a transmission to the specified I2C slave device, equivalent of Wire.beginTransmission in Ar...
Runtime::i2cRead
virtual int i2cRead()=0
Reads a byte from I2C bus, equivalent of Wire.read in Arduino.
Runtime::getPulseDuration
virtual unsigned long getPulseDuration(uint8_t pin, uint8_t state, unsigned long timeout)=0
Gets the incomming pulse length in microseconds starting from the nearest state, equivalent to pulseI...
Runtime::setPWM
virtual void setPWM(uint8_t pin, int dutyCycle)=0
Set PWM state, equivalent of analogWrite in Arduino.
Runtime::getLowState
virtual uint8_t getLowState() const =0
Get the runtime-specific value representing a logical LOW voltage state.
Runtime::i2cRequestFrom
virtual uint8_t i2cRequestFrom(uint8_t address, uint8_t numberOfBytes)=0
Request a number of bytes from the specified I2C slave, equivalent of Wire.requestFrom in Arduino.
Runtime::currentTimeMillis
virtual unsigned long currentTimeMillis()=0
Gets the amount of milliseconds since the microcontroller started running, equivalent of millis in Ar...
Runtime::i2cAvailable
virtual int i2cAvailable()=0
Gets the number of bytes available to be retrieved, equivalent of Wire.availableO in Arduino.
Runtime::currentTimeMicros
virtual unsigned long currentTimeMicros()=0
Gets the amount of microseconds since the microcontroller started running, equivalent of micros in Ar...
Runtime::getInputState
virtual uint8_t getInputState() const =0
Get the runtime-specific value representing an INPUT pin state.
Runtime::setPinDirection
virtual void setPinDirection(uint8_t pin, uint8_t direction)=0
Set pin direction, equivalent of pinMode in Arduino.
Runtime::~Runtime
virtual ~Runtime()=default
Runtime::pinToInterrupt
virtual int8_t pinToInterrupt(uint8_t pin)=0
Gets the interrupt number of the specified pin, equivalent of digitalPinToInterrupt in Arduino.
Runtime::i2cWrite
virtual size_t i2cWrite(uint8_t value)=0
Send the specified byte via i2c, equivalent of Wire.write in Arduino.
Runtime::getAnalogPinState
virtual int getAnalogPinState(uint8_t pin)=0
Get pin's analog (ADC) reading, equivalent of analogRead in Arduino.