Smartcar Shield
Public Member Functions | List of all members
Runtime Interface Referenceabstract

#include <Runtime.hpp>

Inheritance diagram for Runtime:
Inheritance graph
Collaboration diagram for Runtime:
Collaboration graph

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.availableO 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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ~Runtime()

virtual Runtime::~Runtime ( )
virtualdefault

Member Function Documentation

◆ currentTimeMicros()

virtual unsigned long Runtime::currentTimeMicros ( )
pure virtual

Gets the amount of microseconds since the microcontroller started running, equivalent of micros in Arduino.

Returns
Microseconds since beginning of operation

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ currentTimeMillis()

virtual unsigned long Runtime::currentTimeMillis ( )
pure virtual

Gets the amount of milliseconds since the microcontroller started running, equivalent of millis in Arduino.

Returns
Milliseconds since beginning of operation

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ delayMicros()

virtual void Runtime::delayMicros ( unsigned int  microseconds)
pure virtual

Block the execution for the specified number of microseconds, equivalent of delayMicroseconds in Arduino.

Parameters
microsecondsHow much time to block execution in microseconds

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ delayMillis()

virtual void Runtime::delayMillis ( unsigned long  milliseconds)
pure virtual

Block the execution for the specified number of milliseconds, equivalent of delay in Arduino.

Parameters
millisecondsHow much time to block execution in milliseconds

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ getAnalogPinState()

virtual int Runtime::getAnalogPinState ( uint8_t  pin)
pure virtual

Get pin's analog (ADC) reading, equivalent of analogRead in Arduino.

Parameters
pinPin to get ADC reading
Returns
ADC reading

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ getHighState()

virtual uint8_t Runtime::getHighState ( ) const
pure virtual

Get the runtime-specific value representing a logical HIGH voltage state.

Returns
uint8_t The HIGH value

Implemented in ArduinoRuntime.

◆ getInputState()

virtual uint8_t Runtime::getInputState ( ) const
pure virtual

Get the runtime-specific value representing an INPUT pin state.

Returns
uint8_t The INPUT state

Implemented in ArduinoRuntime.

◆ getLowState()

virtual uint8_t Runtime::getLowState ( ) const
pure virtual

Get the runtime-specific value representing a logical LOW voltage state.

Returns
uint8_t The LOW value

Implemented in ArduinoRuntime.

◆ getOutputState()

virtual uint8_t Runtime::getOutputState ( ) const
pure virtual

Get the runtime-specific value representing an OUTPUT pin state.

Returns
uint8_t The OUTPUT state

Implemented in ArduinoRuntime.

◆ getPinState()

virtual int Runtime::getPinState ( uint8_t  pin)
pure virtual

Get the pin state, equivalent of digitalRead in Arduino.

Parameters
pinPin to get state
Returns
Pin's state (i.e. HIGH or LOW)

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ getPulseDuration()

virtual unsigned long Runtime::getPulseDuration ( uint8_t  pin,
uint8_t  state,
unsigned long  timeout 
)
pure virtual

Gets the incomming pulse length in microseconds starting from the nearest state, equivalent to pulseIn in Arduino.

Parameters
pinThe pin to expect the pulse
stateThe state (HIGH or LOW) of the incoming pulse
timeoutHow long to wait for a complete pulse in microseconds
Returns
0 if no pulse arrived otherwise the pulse length in in microseconds

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ getRisingEdgeMode()

virtual int Runtime::getRisingEdgeMode ( ) const
pure virtual

Get the rising edge constant for setting an interrupt.

Returns
int The rising edge mode

Implemented in ArduinoRuntime.

◆ i2cAvailable()

virtual int Runtime::i2cAvailable ( )
pure virtual

Gets the number of bytes available to be retrieved, equivalent of Wire.availableO in Arduino.

Returns
The number of bytes available for reading

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ i2cBeginTransmission()

virtual void Runtime::i2cBeginTransmission ( uint8_t  address)
pure virtual

Initiate a transmission to the specified I2C slave device, equivalent of Wire.beginTransmission in Arduino.

Parameters
addressI2C address to begin a transmission to

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ i2cEndTransmission()

virtual uint8_t Runtime::i2cEndTransmission ( )
pure virtual

Ends a transmission to an I2C device equivalent of Wire.endTransmission in Arduino.

Returns
Transmission status

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ i2cInit()

virtual void Runtime::i2cInit ( )
pure virtual

Initialize I2C bus as master, equivalent of Wire.begin in Arduino.

Implemented in ArduinoRuntime.

◆ i2cRead()

virtual int Runtime::i2cRead ( )
pure virtual

Reads a byte from I2C bus, equivalent of Wire.read in Arduino.

Returns
Byte read from I2C

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ i2cRequestFrom()

virtual uint8_t Runtime::i2cRequestFrom ( uint8_t  address,
uint8_t  numberOfBytes 
)
pure virtual

Request a number of bytes from the specified I2C slave, equivalent of Wire.requestFrom in Arduino.

Parameters
addressI2C slave device address
numberOfBytesNumber of bytes to request
Returns
Number of bytes returned from the slave

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ i2cWrite()

virtual size_t Runtime::i2cWrite ( uint8_t  value)
pure virtual

Send the specified byte via i2c, equivalent of Wire.write in Arduino.

Parameters
valueByte to send
Returns
Number of bytes sent

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ pinToInterrupt()

virtual int8_t Runtime::pinToInterrupt ( uint8_t  pin)
pure virtual

Gets the interrupt number of the specified pin, equivalent of digitalPinToInterrupt in Arduino.

Parameters
pinPin to get interrupt number
Returns
Interrupt number

Implemented in ArduinoRuntime.

◆ setInterrupt()

virtual void Runtime::setInterrupt ( uint8_t  pin,
InterruptCallback  callback,
int  mode 
)
pure virtual

Enables an external hardware interrupt and provides a callback, equivalent to attachInterrupt in Arduino.

Parameters
pinThe interrupt pin to attach the interrupt
callbackThe callback to be executed
modeThe state of the pin to run the callback

Implemented in ArduinoRuntime.

◆ setPinDirection()

virtual void Runtime::setPinDirection ( uint8_t  pin,
uint8_t  direction 
)
pure virtual

Set pin direction, equivalent of pinMode in Arduino.

Parameters
pinThe pin to set direction
directionThe pin's direction (e.g. INPUT, OUTPUT etc)

Implemented in ArduinoRuntime.

◆ setPinState()

virtual void Runtime::setPinState ( uint8_t  pin,
uint8_t  state 
)
pure virtual

Set pin state, equivalent of digitalWrite in Arduino.

Parameters
pinThe pin to set state
stateThe pin's state (i.e. HIGH or LOW)

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

◆ setPWM()

virtual void Runtime::setPWM ( uint8_t  pin,
int  dutyCycle 
)
pure virtual

Set PWM state, equivalent of analogWrite in Arduino.

Parameters
pinPin to set PWM
dutyCycleDuty cycle of PWM

Implemented in ArduinoRuntime.

Here is the caller graph for this function:

The documentation for this interface was generated from the following file: