Smartcar Shield
|
#include <Runtime.hpp>
Public Member Functions | |
virtual | ~Runtime ()=default |
virtual void | setPinDirection (uint8_t pin, uint8_t direction)=0 |
Set pin direction, equivalent of pinMode in Arduino. More... | |
virtual void | setPinState (uint8_t pin, uint8_t state)=0 |
Set pin state, equivalent of digitalWrite in Arduino. More... | |
virtual int | getPinState (uint8_t pin)=0 |
Get the pin state, equivalent of digitalRead in Arduino. More... | |
virtual int | getAnalogPinState (uint8_t pin)=0 |
Get pin's analog (ADC) reading, equivalent of analogRead in Arduino. More... | |
virtual void | setPWM (uint8_t pin, int dutyCycle)=0 |
Set PWM state, equivalent of analogWrite in Arduino. More... | |
virtual void | i2cInit ()=0 |
Initialize I2C bus as master, equivalent of Wire.begin in Arduino. More... | |
virtual void | i2cBeginTransmission (uint8_t address)=0 |
Initiate a transmission to the specified I2C slave device, equivalent of Wire.beginTransmission in Arduino. More... | |
virtual size_t | i2cWrite (uint8_t value)=0 |
Send the specified byte via i2c, equivalent of Wire.write in Arduino. More... | |
virtual uint8_t | i2cEndTransmission ()=0 |
Ends a transmission to an I2C device equivalent of Wire.endTransmission in Arduino. More... | |
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. More... | |
virtual int | i2cAvailable ()=0 |
Gets the number of bytes available to be retrieved, equivalent of Wire.available O in Arduino. More... | |
virtual int | i2cRead ()=0 |
Reads a byte from I2C bus, equivalent of Wire.read in Arduino. More... | |
virtual int8_t | pinToInterrupt (uint8_t pin)=0 |
Gets the interrupt number of the specified pin, equivalent of digitalPinToInterrupt in Arduino. More... | |
virtual unsigned long | currentTimeMillis ()=0 |
Gets the amount of milliseconds since the microcontroller started running, equivalent of millis in Arduino. More... | |
virtual unsigned long | currentTimeMicros ()=0 |
Gets the amount of microseconds since the microcontroller started running, equivalent of micros in Arduino. More... | |
virtual void | delayMillis (unsigned long milliseconds)=0 |
Block the execution for the specified number of milliseconds, equivalent of delay in Arduino. More... | |
virtual void | delayMicros (unsigned int microseconds)=0 |
Block the execution for the specified number of microseconds, equivalent of delayMicroseconds in Arduino. More... | |
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 pulseIn in Arduino. More... | |
virtual void | setInterrupt (uint8_t pin, InterruptCallback callback, int mode)=0 |
Enables an external hardware interrupt and provides a callback, equivalent to attachInterrupt in Arduino. More... | |
virtual uint8_t | getLowState () const =0 |
Get the runtime-specific value representing a logical LOW voltage state. More... | |
virtual uint8_t | getHighState () const =0 |
Get the runtime-specific value representing a logical HIGH voltage state. More... | |
virtual uint8_t | getOutputState () const =0 |
Get the runtime-specific value representing an OUTPUT pin state. More... | |
virtual uint8_t | getInputState () const =0 |
Get the runtime-specific value representing an INPUT pin state. More... | |
virtual int | getRisingEdgeMode () const =0 |
Get the rising edge constant for setting an interrupt. More... | |
An interface to serve as a wrapper for the native runtime environment, greatly inspired by the Arduino library API. Its purpose is to facilitate testing and porting onto different platforms. All used environment (e.g. Arduino) free functions should be included in this interface so they can be mocked in tests and ported to different environments.
Definition at line 35 of file Runtime.hpp.
|
virtualdefault |
|
pure virtual |
Gets the amount of microseconds since the microcontroller started running, equivalent of micros
in Arduino.
Implemented in ArduinoRuntime.
|
pure virtual |
Gets the amount of milliseconds since the microcontroller started running, equivalent of millis
in Arduino.
Implemented in ArduinoRuntime.
|
pure virtual |
Block the execution for the specified number of microseconds, equivalent of delayMicroseconds
in Arduino.
microseconds | How much time to block execution in microseconds |
Implemented in ArduinoRuntime.
|
pure virtual |
Block the execution for the specified number of milliseconds, equivalent of delay
in Arduino.
milliseconds | How much time to block execution in milliseconds |
Implemented in ArduinoRuntime.
|
pure virtual |
Get pin's analog (ADC) reading, equivalent of analogRead
in Arduino.
pin | Pin to get ADC reading |
Implemented in ArduinoRuntime.
|
pure virtual |
Get the runtime-specific value representing a logical HIGH
voltage state.
HIGH
value Implemented in ArduinoRuntime.
|
pure virtual |
Get the runtime-specific value representing an INPUT
pin state.
INPUT
state Implemented in ArduinoRuntime.
|
pure virtual |
Get the runtime-specific value representing a logical LOW
voltage state.
LOW
value Implemented in ArduinoRuntime.
|
pure virtual |
Get the runtime-specific value representing an OUTPUT
pin state.
OUTPUT
state Implemented in ArduinoRuntime.
|
pure virtual |
Get the pin state, equivalent of digitalRead
in Arduino.
pin | Pin to get state |
Implemented in ArduinoRuntime.
|
pure virtual |
Gets the incomming pulse length in microseconds starting from the nearest state
, equivalent to pulseIn
in Arduino.
pin | The pin to expect the pulse |
state | The state (HIGH or LOW ) of the incoming pulse |
timeout | How long to wait for a complete pulse in microseconds |
0
if no pulse arrived otherwise the pulse length in in microseconds Implemented in ArduinoRuntime.
|
pure virtual |
Get the rising edge constant for setting an interrupt.
Implemented in ArduinoRuntime.
|
pure virtual |
Gets the number of bytes available to be retrieved, equivalent of Wire.available
O in Arduino.
Implemented in ArduinoRuntime.
|
pure virtual |
Initiate a transmission to the specified I2C slave device, equivalent of Wire.beginTransmission
in Arduino.
address | I2C address to begin a transmission to |
Implemented in ArduinoRuntime.
|
pure virtual |
Ends a transmission to an I2C device equivalent of Wire.endTransmission
in Arduino.
Implemented in ArduinoRuntime.
|
pure virtual |
Initialize I2C bus as master, equivalent of Wire.begin
in Arduino.
Implemented in ArduinoRuntime.
|
pure virtual |
Reads a byte from I2C bus, equivalent of Wire.read
in Arduino.
Implemented in ArduinoRuntime.
|
pure virtual |
Request a number of bytes from the specified I2C slave, equivalent of Wire.requestFrom
in Arduino.
address | I2C slave device address |
numberOfBytes | Number of bytes to request |
Implemented in ArduinoRuntime.
|
pure virtual |
Send the specified byte via i2c, equivalent of Wire.write
in Arduino.
value | Byte to send |
Implemented in ArduinoRuntime.
|
pure virtual |
Gets the interrupt number of the specified pin, equivalent of digitalPinToInterrupt
in Arduino.
pin | Pin to get interrupt number |
Implemented in ArduinoRuntime.
|
pure virtual |
Enables an external hardware interrupt and provides a callback, equivalent to attachInterrupt
in Arduino.
pin | The interrupt pin to attach the interrupt |
callback | The callback to be executed |
mode | The state of the pin to run the callback |
Implemented in ArduinoRuntime.
|
pure virtual |
Set pin direction, equivalent of pinMode
in Arduino.
pin | The pin to set direction |
direction | The pin's direction (e.g. INPUT , OUTPUT etc) |
Implemented in ArduinoRuntime.
|
pure virtual |
Set pin state, equivalent of digitalWrite
in Arduino.
pin | The pin to set state |
state | The pin's state (i.e. HIGH or LOW ) |
Implemented in ArduinoRuntime.
|
pure virtual |
Set PWM state, equivalent of analogWrite
in Arduino.
pin | Pin to set PWM |
dutyCycle | Duty cycle of PWM |
Implemented in ArduinoRuntime.