platisd / smartcar_shield
1
/**
2
 * \interface Runtime
3
 * An interface to serve as a wrapper for the native runtime environment,
4
 * greatly inspired by the Arduino library API.
5
 * Its purpose is to facilitate testing and porting onto different platforms.
6
 * All used environment (e.g. Arduino) free functions should be included in
7
 * this interface so they can be mocked in tests and ported to different
8
 * environments.
9
 */
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 1
    virtual ~Runtime() = default;
39

40
    /**
41
     * Set pin direction, equivalent of `pinMode` in Arduino
42
     * @param pin       The pin to set direction
43
     * @param direction The pin's direction (e.g. `INPUT`, `OUTPUT` etc)
44
     */
45
    virtual void setPinDirection(uint8_t pin, uint8_t direction) = 0;
46

47
    /**
48
     * Set pin state, equivalent of `digitalWrite` in Arduino
49
     * @param pin   The pin to set state
50
     * @param state The pin's state (i.e. `HIGH` or `LOW`)
51
     */
52
    virtual void setPinState(uint8_t pin, uint8_t state) = 0;
53

54
    /**
55
     * Get the pin state, equivalent of `digitalRead` in Arduino
56
     * @param  pin Pin to get state
57
     * @return     Pin's state (i.e. HIGH or LOW)
58
     */
59
    virtual int getPinState(uint8_t pin) = 0;
60

61
    /**
62
     * Get pin's analog (ADC) reading, equivalent of `analogRead` in Arduino
63
     * @param  pin Pin to get ADC reading
64
     * @return     ADC reading
65
     */
66
    virtual int getAnalogPinState(uint8_t pin) = 0;
67

68
    /**
69
     * Set PWM state, equivalent of `analogWrite` in Arduino
70
     * @param pin       Pin to set PWM
71
     * @param dutyCycle Duty cycle of PWM
72
     */
73
    virtual void setPWM(uint8_t pin, int dutyCycle) = 0;
74

75
    /**
76
     * Initialize I2C bus as master, equivalent of `Wire.begin` in Arduino
77
     */
78
    virtual void i2cInit() = 0;
79

80
    /**
81
     * Initiate a transmission to the specified I2C slave device, equivalent
82
     * of `Wire.beginTransmission` in Arduino
83
     * @param address I2C address to begin a transmission to
84
     */
85
    virtual void i2cBeginTransmission(uint8_t address) = 0;
86

87
    /**
88
     * Send the specified byte via i2c, equivalent of `Wire.write` in Arduino
89
     * @param  value Byte to send
90
     * @return       Number of bytes sent
91
     */
92
    virtual size_t i2cWrite(uint8_t value) = 0;
93

94
    /**
95
     * Ends a transmission to an I2C device equivalent of
96
     * `Wire.endTransmission` in Arduino
97
     * @return Transmission status
98
     */
99
    virtual uint8_t i2cEndTransmission() = 0;
100

101
    /**
102
     * Request a number of bytes from the specified I2C slave, equivalent of
103
     * `Wire.requestFrom` in Arduino
104
     * @param  address       I2C slave device address
105
     * @param  numberOfBytes Number of bytes to request
106
     * @return               Number of bytes returned from the slave
107
     */
108
    virtual uint8_t i2cRequestFrom(uint8_t address, uint8_t numberOfBytes) = 0;
109

110
    /**
111
     * Gets the number of bytes available to be retrieved, equivalent of
112
     * `Wire.available`O in Arduino
113
     * @return The number of bytes available for reading
114
     */
115
    virtual int i2cAvailable() = 0;
116

117
    /**
118
     * Reads a byte from I2C bus, equivalent of `Wire.read` in Arduino
119
     * @return Byte read from I2C
120
     */
121
    virtual int i2cRead() = 0;
122

123
    /**
124
     * Gets the interrupt number of the specified pin, equivalent of
125
     * `digitalPinToInterrupt` in Arduino
126
     * @param  pin Pin to get interrupt number
127
     * @return     Interrupt number
128
     */
129
    virtual int8_t pinToInterrupt(uint8_t pin) = 0;
130

131
    /**
132
     * Gets the amount of milliseconds since the microcontroller started
133
     * running, equivalent of `millis` in Arduino
134
     * @return Milliseconds since beginning of operation
135
     */
136
    virtual unsigned long currentTimeMillis() = 0;
137

138
    /**
139
     * Gets the amount of microseconds since the microcontroller started
140
     * running, equivalent of `micros` in Arduino
141
     * @return Microseconds since beginning of operation
142
     */
143
    virtual unsigned long currentTimeMicros() = 0;
144

145
    /**
146
     * Block the execution for the specified number of milliseconds, equivalent
147
     * of `delay` in Arduino
148
     * @param milliseconds How much time to block execution in milliseconds
149
     */
150
    virtual void delayMillis(unsigned long milliseconds) = 0;
151

152
    /**
153
     * Block the execution for the specified number of microseconds, equivalent
154
     * of `delayMicroseconds` in Arduino
155
     * @param microseconds How much time to block execution in microseconds
156
     */
157
    virtual void delayMicros(unsigned int microseconds) = 0;
158

159
    /**
160
     * Gets the incomming pulse length in microseconds starting from the nearest
161
     * `state`, equivalent to `pulseIn` in Arduino
162
     * @param  pin     The pin to expect the pulse
163
     * @param  state   The state (`HIGH` or `LOW`) of the incoming pulse
164
     * @param  timeout How long to wait for a complete pulse in microseconds
165
     * @return         `0` if no pulse arrived otherwise the pulse length in
166
     *                     in microseconds
167
     */
168
    virtual unsigned long getPulseDuration(uint8_t pin, uint8_t state, unsigned long timeout) = 0;
169

170
    /**
171
     * Enables an external hardware interrupt and provides a callback, equivalent to
172
     * `attachInterrupt` in Arduino
173
     * @param pin       The interrupt pin to attach the interrupt
174
     * @param callback  The callback to be executed
175
     * @param mode      The state of the pin to run the callback
176
     */
177
    virtual void setInterrupt(uint8_t pin, InterruptCallback callback, int mode) = 0;
178

179
    /**
180
     * @brief Get the runtime-specific value representing a logical `LOW` voltage state
181
     *
182
     * @return uint8_t The `LOW` value
183
     */
184
    virtual uint8_t getLowState() const = 0;
185

186
    /**
187
     * @brief Get the runtime-specific value representing a logical `HIGH` voltage state
188
     *
189
     * @return uint8_t The `HIGH` value
190
     */
191
    virtual uint8_t getHighState() const = 0;
192

193
    /**
194
     * @brief Get the runtime-specific value representing an `OUTPUT` pin state
195
     *
196
     * @return uint8_t The `OUTPUT` state
197
     */
198
    virtual uint8_t getOutputState() const = 0;
199

200
    /**
201
     * @brief Get the runtime-specific value representing an `INPUT` pin state
202
     *
203
     * @return uint8_t The `INPUT` state
204
     */
205
    virtual uint8_t getInputState() const = 0;
206

207
    /**
208
     * @brief Get the rising edge constant for setting an interrupt
209
     *
210
     * @return int The rising edge mode
211
     */
212
    virtual int getRisingEdgeMode() const = 0;
213
};

Read our documentation on viewing source code .

Loading