Skip to content

Commit

Permalink
[Issue EnviroDIY#66]ESP32/8266 Has a micro second free running timer …
Browse files Browse the repository at this point in the history
…so we have

no need to configurea time for these.
 1. Change the names to the states  proefixing them with SDI12_ to
eliminate confilct with ESP hall files .
 2. Created a new READTIME macro  to replace  TCNTX this id defined  in
SDI12.h This helps to reduce the conditional platform specific code from
the main driver files.
 3. Introduced a typedef conditional on platform for the READ TIME
value.
  • Loading branch information
peterj43 committed May 29, 2020
1 parent 8543d95 commit 8bb4f1f
Show file tree
Hide file tree
Showing 4 changed files with 121 additions and 74 deletions.
136 changes: 70 additions & 66 deletions src/SDI12.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,17 +130,17 @@ SDI12 *SDI12::_activeObject = NULL; // Pointer to active SDI12 object
#include "SDI12_boards.h" // Include timer information
SDI12Timer sdi12timer; // Timer functions

static const uint16_t bitWidth_micros = (uint16_t) 833; // The size of a bit in microseconds
static const uint16_t bitWidth_micros = (uint16_t) 833; // The size of a bit in microseconds
// 1200 baud = 1200 bits/second ~ 833.333 µs/bit
static const uint16_t lineBreak_micros = (uint16_t) 12300; // The required "break" before sending commands
// break >= 12ms
static const uint16_t marking_micros = (uint16_t) 8500; // The required mark before a command or response
static const uint16_t marking_micros = (uint16_t) 8500; // The required mark before a command or response
// marking >= 8.33ms

static const uint8_t txBitWidth = TICKS_PER_BIT;
static const uint8_t rxWindowWidth = RX_WINDOW_FUDGE; // A fudge factor to make things work
static const uint8_t bitsPerTick_Q10 = BITS_PER_TICK_Q10;
static const uint8_t WAITING_FOR_START_BIT = 0xFF; // 0b11111111
static const uint8_t txBitWidth = TICKS_PER_BIT;
static const uint8_t rxWindowWidth = RX_WINDOW_FUDGE; // A fudge factor to make things work
static const uint8_t bitsPerTick_Q10 = BITS_PER_TICK_Q10;
static const uint8_t WAITING_FOR_START_BIT = 0xFF; // 0b11111111

static uint16_t prevBitTCNT; // previous RX transition in micros
static uint8_t rxState; // 0: got start bit; >0: bits rcvd
Expand Down Expand Up @@ -387,7 +387,7 @@ private variable "_dataPin".
3.2 - When the destructor is called, it's main task is to disable any
interrupts that had been previously assigned to the pin, so that the pin
will behave as expected when used for other purposes. This is achieved
by putting the SDI-12 object in the DISABLED state.
by putting the SDI-12 object in the SDI12_DISABLED state.

3.3 - This is called to begin the functionality of the SDI-12 object. It
has no parameters as the SDI-12 protocol is fully specified (e.g. the
Expand All @@ -414,7 +414,7 @@ SDI12::SDI12(uint8_t dataPin){

// 3.2 Destructor
SDI12::~SDI12(){
setState(DISABLED);
setState(SDI12_DISABLED);
_activeObject = NULL;
// Set the timer prescalers back to original values
// NOTE: This does NOT reset SAMD board pre-scalers!
Expand All @@ -423,7 +423,7 @@ SDI12::~SDI12(){

// 3.3 Begin
void SDI12::begin(){
// setState(HOLDING);
// setState(SDI12_HOLDING);
setActive();
// SDI-12 protocol says sensors must respond within 15 milliseconds
// We'll bump that up to 150, just for good measure, but we don't want to
Expand All @@ -447,7 +447,7 @@ void SDI12::begin(uint8_t dataPin){
// 3.4 End
void SDI12::end()
{
setState(DISABLED);
setState(SDI12_DISABLED);
_activeObject = NULL;
// Set the timer prescalers back to original values
// NOTE: This does NOT reset SAMD board pre-scalers!
Expand All @@ -465,7 +465,7 @@ uint8_t SDI12::getDataPin() { return _dataPin; }

This library is allows for multiple instances of itself running on the same or
different pins. SDI-12 can support up to 62 sensors on a single pin/bus,
so it is notnecessary to use an instance for each sensor.
so it is not necessary to use an instance for each sensor.

Because we are using pin change interrupts there can only be one active
object at a time (since this is the only reliable way to determine which
Expand All @@ -479,7 +479,7 @@ on the other pin. For proper behavior it is recommended to use this
myOtherSDI12.setActive();

Other notes: Promoting an object into the Active state will set it as
HOLDING. See 4.1 for more information.
SDI12_HOLDING. See 4.1 for more information.

Calling mySDI12.begin() will assert mySDI12 as the new active object,
until another instance calls myOtherSDI12.begin() or
Expand All @@ -496,7 +496,7 @@ returns TRUE if the object was not formerly the active object and now
is. returns

Promoting an inactive to the active instance will start it in the
HOLDING state and return TRUE.
SDI12_HOLDING state and return TRUE.

Otherwise, if the object is currently the active instance, it will
remain unchanged and return FALSE.
Expand All @@ -511,7 +511,7 @@ bool SDI12::setActive()
{
if (_activeObject != this)
{
setState(HOLDING);
setState(SDI12_HOLDING);
_activeObject = this;
return true;
}
Expand All @@ -528,24 +528,24 @@ The Arduino is responsible for managing communication with the sensors.
Since all the data transfer happens on the same line, the state of the
data line is very important.

When the pin is in the HOLDING state, it is holding the line LOW so that
When the pin is in the SDI12_HOLDING state, it is holding the line LOW so that
interference does not unintentionally wake the sensors up. The interrupt
is disabled for the dataPin, because we are not expecting any SDI-12
traffic. In the TRANSMITTING state, we would like exclusive control of
traffic. In the SDI12_TRANSMITTING state, we would like exclusive control of
the Arduino, so we shut off all interrupts, and vary the voltage of the
dataPin in order to wake up and send commands to the sensor. In the
LISTENING state, we are waiting for a sensor to respond, so we drop the
SDI12_LISTENING state, we are waiting for a sensor to respond, so we drop the
voltage level to LOW and relinquish control (INPUT). If we would like to
disable all SDI-12 functionality, then we set the system to the DISABLED
state, removing the interrupt associated with the dataPin. For
predictability, we set the pin to a LOW level high impedance state
disable all SDI-12 functionality, then we set the system to the
SDI12_DISABLED state, removing the interrupt associated with the dataPin.
For predictability, we set the pin to a LOW level high impedance state
(INPUT).

State Interrupts Pin Mode Pin Level
HOLDING Pin Disable OUTPUT LOW
TRANSMITTING All/Pin Disable OUTPUT VARYING
LISTENING All Enable INPUT LOW
DISABLED Pin Disable INPUT LOW
SDI12_HOLDING Pin Disable OUTPUT LOW
SDI12_TRANSMITTING All/Pin Disable OUTPUT VARYING
SDI12_LISTENING All Enable INPUT LOW
SDI12_DISABLED Pin Disable INPUT LOW

------------------------------| Sequencing |------------------------------

Expand Down Expand Up @@ -580,7 +580,7 @@ relinquish control of the data line when not transmitting.
#include <avr/interrupt.h> // interrupt handling
#include <util/parity.h> // optimized parity bit handling
#else
// Added MJB: parity fuction to replace the one specific for AVR from util/parity.h
// Added MJB: parity function to replace the one specific for AVR from util/parity.h
// http://graphics.stanford.edu/~seander/bithacks.html#ParityNaive
uint8_t SDI12::parity_even_bit(uint8_t v)
{
Expand All @@ -597,7 +597,7 @@ uint8_t SDI12::parity_even_bit(uint8_t v)
// 5.2 - a helper function to switch pin interrupts on or off
void SDI12::setPinInterrupts(bool enable)
{
#if defined (ARDUINO_ARCH_SAMD)
#if defined (ARDUINO_ARCH_SAMD) || defined(ESP32) || defined(ESP8266)
if (enable) attachInterrupt(digitalPinToInterrupt(_dataPin), handleInterrupt, CHANGE); // Merely need to attach the interrupt function to the pin
else detachInterrupt(digitalPinToInterrupt(_dataPin)); // Merely need to detach the interrupt function from the pin

Expand Down Expand Up @@ -630,22 +630,22 @@ void SDI12::setPinInterrupts(bool enable)
void SDI12::setState(SDI12_STATES state){
switch (state)
{
case HOLDING:
case SDI12_HOLDING:
{
pinMode(_dataPin, INPUT); // Turn off the pull-up resistor
pinMode(_dataPin, OUTPUT); // Pin mode = output
digitalWrite(_dataPin, LOW); // Pin state = low - hold the line low
setPinInterrupts(false); // Interrupts disabled on data pin
break;
}
case TRANSMITTING:
case SDI12_TRANSMITTING:
{
pinMode(_dataPin, INPUT); // Turn off the pull-up resistor
pinMode(_dataPin, OUTPUT); // Pin mode = output
setPinInterrupts(false); // Interrupts disabled on data pin
break;
}
case LISTENING:
case SDI12_LISTENING:
{
digitalWrite(_dataPin, LOW); // Pin state = low
pinMode(_dataPin, INPUT); // Pin mode = input, pull-up resistor off
Expand All @@ -654,7 +654,7 @@ void SDI12::setState(SDI12_STATES state){
rxState = WAITING_FOR_START_BIT;
break;
}
default: // DISABLED or ENABLED
default: // SDI12_DISABLED or SDI12_ENABLED
{
digitalWrite(_dataPin, LOW); // Pin state = low
pinMode(_dataPin, INPUT); // Pin mode = input, pull-up resistor off
Expand All @@ -664,14 +664,14 @@ void SDI12::setState(SDI12_STATES state){
}
}

// 5.4 - forces a HOLDING state.
// 5.4 - forces a SDI12_HOLDING state.
void SDI12::forceHold(){
setState(HOLDING);
setState(SDI12_HOLDING);
}

// 5.5 - forces a LISTENING state.
// 5.5 - forces a SDI12_LISTENING state.
void SDI12::forceListen(){
setState(LISTENING);
setState(SDI12_LISTENING);
}


Expand All @@ -680,8 +680,8 @@ void SDI12::forceListen(){
6.1 - wakeSensors() literally wakes up all the sensors on the bus. The
SDI-12 protocol requires a pulse of HIGH voltage for at least 12
milliseconds followed immediately by a pulse of LOW voltage for at least
8.3 milliseconds. Setting the SDI-12 object into the TRANSMITTING allows us to
assert control of the line without triggering any interrupts.
8.3 milliseconds. Setting the SDI-12 object into the SDI12_TRANSMITTING allows
us to assert control of the line without triggering any interrupts.

6.2 - This function writes a character out to the data line. SDI-12
specifies the general transmission format of a single character as:
Expand Down Expand Up @@ -712,7 +712,7 @@ recorder for another SDI-12 device

// 6.1 - this function wakes up the entire sensor bus
void SDI12::wakeSensors() {
setState(TRANSMITTING);
setState(SDI12_TRANSMITTING);
// Universal interrupts can be on while the break and marking happen because
// timings for break and from the recorder are not critical.
// Interrupts on the pin are disabled for the entire transmitting state
Expand All @@ -724,33 +724,35 @@ void SDI12::wakeSensors() {

// 6.2 - this function writes a character out on the data line
void SDI12::writeChar(uint8_t outChar) {
uint8_t currentTxBitNum = 0; // first bit is start bit
uint8_t bitValue = 1; // start bit is HIGH (inverse parity...)
uint8_t currentTxBitNum = 0; // first bit is start bit
uint8_t bitValue = 1; // start bit is HIGH (inverse parity...)

noInterrupts(); // _ALL_ interrupts disabled so timing can't be shifted
noInterrupts(); // _ALL_ interrupts disabled so timing can't be shifted

sdi12timer_t t0 = READTIME; // start time

uint8_t t0 = TCNTX; // start time
digitalWrite(_dataPin, HIGH); // immediately get going on the start bit
// this gives us 833µs to calculate parity and position of last high bit
// this gives us 833µs to calculate parity and position of last high bit
currentTxBitNum++;

uint8_t parityBit = parity_even_bit(outChar); // Calculate the parity bit
outChar |= (parityBit<<7); // Add parity bit to the outgoing character
outChar |= (parityBit<<7); // Add parity bit to the outgoing character

// Calculate the position of the last bit that is a 0/HIGH (ie, HIGH, not marking)
// That bit will be the last time-critical bit. All bits after that can be
// sent with interrupts enabled.

uint8_t lastHighBit = 9; // The position of the last bit that is a 0 (ie, HIGH, not marking)
uint8_t msbMask = 0x80; // A mask with all bits at 1
uint8_t lastHighBit = 9; // The position of the last bit that is a 0 (ie, HIGH, not marking)
uint8_t msbMask = 0x80; // A mask with all bits at 1
while (msbMask & outChar) {
lastHighBit--;
msbMask >>= 1;
}

// Hold the line for the rest of the start bit duration
while ((uint8_t)(TCNTX - t0) < txBitWidth) {}
t0 = TCNTX; // advance start time

while ((uint8_t)(READTIME - t0) < txBitWidth) {}
t0 = READTIME; // advance start time

// repeat for all data bits until the last bit different from marking
while (currentTxBitNum++ < lastHighBit) {
Expand All @@ -762,8 +764,9 @@ void SDI12::writeChar(uint8_t outChar) {
digitalWrite(_dataPin, HIGH); // set the pin state to HIGH for 0's
}
// Hold the line for this bit duration
while ((uint8_t)(TCNTX - t0) < txBitWidth) {}
t0 = TCNTX; // advance start time
while ((uint8_t)(READTIME - t0) < txBitWidth) {}
t0 = READTIME; // start time

outChar = outChar >> 1; // shift character to expose the following bit
}

Expand All @@ -774,18 +777,17 @@ void SDI12::writeChar(uint8_t outChar) {

// Hold the line low until the end of the 10th bit
uint8_t bitTimeRemaining = txBitWidth*(10-lastHighBit);
while ((uint8_t)(TCNTX - t0) < bitTimeRemaining) {}

while ((uint8_t)(READTIME - t0) < bitTimeRemaining) {}
}

// The typical write functionality for a stream object
// This allows you to use the stream print functions to send commands out on
// the SDI-12, line, but it will not wake the sensors in advance of the command.
size_t SDI12::write(uint8_t byte) {
setState(TRANSMITTING);
writeChar(byte); // write the character/byte
setState(LISTENING); // listen for reply
return 1; // 1 character sent
setState(SDI12_TRANSMITTING);
writeChar(byte); // write the character/byte
setState(SDI12_LISTENING); // listen for reply
return 1; // 1 character sent
}

// 6.3 - this function sends out the characters of the String cmd, one by one
Expand All @@ -794,57 +796,57 @@ void SDI12::sendCommand(String &cmd) {
for (int unsigned i = 0; i < cmd.length(); i++){
writeChar(cmd[i]); // write each character
}
setState(LISTENING); // listen for reply
setState(SDI12_LISTENING); // listen for reply
}

void SDI12::sendCommand(const char *cmd) {
wakeSensors(); // wake up sensors
for (int unsigned i = 0; i < strlen(cmd); i++){
writeChar(cmd[i]); // write each character
}
setState(LISTENING); // listen for reply
setState(SDI12_LISTENING); // listen for reply
}

void SDI12::sendCommand(FlashString cmd) {
wakeSensors(); // wake up sensors
for (int unsigned i = 0; i < strlen_P((PGM_P)cmd); i++){
writeChar((char)pgm_read_byte((const char *)cmd + i)); // write each character
}
setState(LISTENING); // listen for reply
setState(SDI12_LISTENING); // listen for reply
}

// 6.4 - this function sets up for a response to a separate data recorder by
// sending out a marking and then sending out the characters of resp
// one by one (for slave-side use, that is, when the Arduino itself is
// acting as an SDI-12 device rather than a recorder).
void SDI12::sendResponse(String &resp) {
setState(TRANSMITTING); // Get ready to send data to the recorder
setState(SDI12_TRANSMITTING); // Get ready to send data to the recorder
digitalWrite(_dataPin, LOW);
delayMicroseconds(marking_micros); // 8.33 ms marking before response
for (int unsigned i = 0; i < resp.length(); i++){
writeChar(resp[i]); // write each character
}
setState(LISTENING); // return to listening state
setState(SDI12_LISTENING); // return to listening state
}

void SDI12::sendResponse(const char *resp) {
setState(TRANSMITTING); // Get ready to send data to the recorder
setState(SDI12_TRANSMITTING); // Get ready to send data to the recorder
digitalWrite(_dataPin, LOW);
delayMicroseconds(marking_micros); // 8.33 ms marking before response
for (int unsigned i = 0; i < strlen(resp); i++){
writeChar(resp[i]); // write each character
}
setState(LISTENING); // return to listening state
setState(SDI12_LISTENING); // return to listening state
}

void SDI12::sendResponse(FlashString resp) {
setState(TRANSMITTING); // Get ready to send data to the recorder
setState(SDI12_TRANSMITTING); // Get ready to send data to the recorder
digitalWrite(_dataPin, LOW);
delayMicroseconds(marking_micros); // 8.33 ms marking before response
for (int unsigned i = 0; i < strlen_P((PGM_P)resp); i++){
writeChar((char)pgm_read_byte((const char *)resp + i)); // write each character
}
setState(LISTENING); // return to listening state
setState(SDI12_LISTENING); // return to listening state
}


Expand Down Expand Up @@ -892,7 +894,9 @@ void SDI12::startChar()
// 7.3 - The actual interrupt service routine
void SDI12::receiveISR()
{
uint8_t thisBitTCNT = TCNTX; // time of this data transition (plus ISR latency)

sdi12timer_t thisBitTCNT = READTIME; // time of this data transition (plus ISR latency)

uint8_t pinLevel = digitalRead(_dataPin); // current RX data level

// Check if we're ready for a start bit, and if this could possibly be it
Expand All @@ -914,7 +918,7 @@ void SDI12::receiveISR()

// check how many bit times have passed since the last change
// the rxWindowWidth is just a fudge factor
uint16_t rxBits = bitTimes(thisBitTCNT - prevBitTCNT);
uint16_t rxBits = bitTimes((uint8_t)(thisBitTCNT - prevBitTCNT));
// Serial.println(rxBits);
// calculate how many *data+parity* bits should be left
// We know the start bit is past and are ignoring the stop bit (which will be LOW/1)
Expand Down
Loading

0 comments on commit 8bb4f1f

Please sign in to comment.