zavracky
Published © GPL3+

Irrigation System

This relatively simple system keeps track of the moisture in the soil and activates up to eight valves for watering plants when necessary.

IntermediateFull instructions provided5,633
Irrigation System

Things used in this project

Hardware components

Arduino Nano R3
Arduino Nano R3
×1
12V Power Supply - RXZ12V2A-A
×1
Raindrip 016010T 1/4-Inch by 100-Feet Black Tubing
×1
Kalolary irrigation fittings
×1
Lantee PG 9 Cable Gland
×4
MAKERELE waterproof outdoor enclosure
×1
Raindrip R325C 3/4-Inch Hose Thread Swivel to 1/4-Inch Tubing Adaptor
×1
22AWG 2 Conductor Wire, 20M/65.6ft Flexible Black PVC Jacketed Hookup Wire
×1
URATOT 60 Pieces 360 Degree Adjustable Irrigation Drippers with Barbed Connector
×1
DZS Elec 2-Pack 5V 4-Channel Relay Module with Optocoupler Active Low Level Amplifier Trigger JD-VCC Relay Power VCC Power
×1
10pcs NRF24L01+ 2.4GHz Wireless RF Transceiver Module
×1
Arduino Mega 2560
Arduino Mega 2560
×1
HiLetgo ILI9341 2.8" SPI TFT LCD Display Touch Panel 240X320 with PCB 5V/3.3V STM32
×1
3D Printer Heatsink Kit + Thermal Conductive Adhesive Tape, Cooler Heat Sink Cooling TMC2130 TMC2100 A4988 DRV8825 TMC2208 Stepper Motor Driver Module (22pcs)
These heatsinks fit very nicely on the BD140 PNP transistors used on the MEGA driver board.
×1
Ogrmar ABS Plastic Dustproof Waterproof IP65 Junction Box Universal Durable Electrical Project Enclosure With Lock (8.6"x6.7"x4.3")
This larger box is better suited for the MEGA irrigation system. It provides plenty of room for the MEGA stack.
×1
Favordrory 6 Pieces 304 Stainless Steel 3mm x 300mm Model Straight Metal Round Shaft Rods
×1
Irwin Hanson 6-32NC Self-Aligning Die
You might be able to get this tool at your local hardware store, as I did.
×1
BTF-LIGHTING 5 Pin Electrical Connector 24AWG IP65 Male Female Connector 7.87in/20cm Extension Cable for Car
×1
22 Gauge 2 Conductor Electrical Wire, 20M/65.6ft Flexible Black PVC Jacketed Hookup Wire, 22 AWG Tinned Copper Extension Cord
×1
1/4" DC 12V Solenoid Valve N/C Normally Closed Water Inlet Flow Switch
×1

Hand tools and fabrication machines

3D Printer (generic)
3D Printer (generic)
Soldering iron (generic)
Soldering iron (generic)

Story

Read more

Custom parts and enclosures

Sensor Support

This is the part that holds the 3mm rods used as the electrodes for the moisture sensor and the Dallas Temperature Sensor.

Watering Valve Enclosure

This enclosure will house three valves.

Watering Valve Enclosure Cover

It's a cover to keep the valves as dry as possible. The holes for the tubing in the side of the enclosure are fairly tight, so it should be possible to at least keep insects out.

Nano Electronics Support Plate

This plate holds the power supply and the Arduino board. It has holds for mounting in the specified waterproof enclosure.

MEGA Electronics Support Plate

This plate attaches to the bottom of the waterproof enclosure and supports the 12Volt power supply and the MEGA stack.

Display Support Post

This is used to hold the display above the sensor board.

Shutoff Valve Enclosure Cover

System Shutoff Valve Enclosure

Schematics

Arduino Nano Circuit Board

System Controller good for up to 8 valves. The Nano is challenged with very little RAM headroom at 8 valves, but works great at 6 valves.

Nano Irrigation Board with Temperature Sensors

This board includes inputs for Dallas Semiconductor Temperature Sensors. My code hasn't been fully tested. I am upgrading to an Arduino MEGA which will incorporate the temperature sensors. I found the program and memory space of the Nano too limiting for over four valves.. You many have better luck.

Arduino Nano Circuit Board

This board does not include temperature sensors and is good for up to 8 valves. (I have been running six valves for a month without issues). The Nano is challenged with very little RAM headroom at 8 valves, but works great at 6 valves.

MEGA Driver Board 2.58

This driver board will stack on an Arduino MEGA and drive 9 valves. This updated version includes LEDs on each of the drive transistor outputs.

MEGA Irrigaton System with Display 2.63

This spin provides the capability of adding a display and adding an NRF24 radio to interface with MySensors and a home automation system. There is flexibility in it's implementation. You can run the system without the NRFradio using the software for that purpose. The board can be assembled without the components for the radio - a connector, capacitor, LED , resistor and the radio. Of course, you must use the software sans MySensors. If you install the radio, then you can use the software with the MySensors interface. In my case, this allows communication with Home Assistant.

This board provides the following interfaces:
MySensors NRF24 Radio
HiLetgo ILI9341 2.8" SPI TFT LCD Display Touch Panel
Backlight control
Moisture Sensor Interface
Dallas Temp Sensor Interface
Valve Control through PORTA

Code

Nano Irrigation_System2.96.ino

C/C++
#define VERSION "2.96"
/* REVISION HISTORY
 *  Written by Paul M. Zavracky
 *  Borrows heavily from the work of zillions of others
 *  
 *  The irrigation system comprises a set of 1 to 8 1/4 12v water valves, a moisture sensor, an arduino, 
 *  an NRF24 Radio, and 8 relays.  The Arduino takes both the digital and analog signals from the 
 *  moisture sensor and uses this information to determine if watering is needed.  If so, the Arduino
 *  sends a signal to the relay board, actualing the appropriate relay.  The relay connects a 12V supply
 *  to the water valve.  The Arduino continues monitoring the moisture sensor.  Once a predetermined level
 *  is reached, the Arduino turns off the water flow.
 *  Uses Larry Bank's Bit Bang I2C library. You can find it here:
 *  https://github.com/bitbank2/BitBang_I2C
 */

// setup for MCP23008 port expander
// definitions for mcp23008
#define MCP23008_ADDR 0x23 //Address of MCP23008
#define IODIR 0x00 // I/O DIRECTION REGISTER 
#define IPOL 0x01 // INPUT POLARITY PORT REGISTER
#define GPINTEN 0x02 // INTERRUPT-ON-CHANGE PINS
#define DEFVAL 0x03 // DEFAULT VALUE REGISTER
#define INTCON 0x04 // INTERRUPT-ON-CHANGE CONTROL REGISTER
#define OCON 0x05 // I/O EXPANDER CONFIGURATION REGISTER
#define GPPU 0x06 // GPIO PULL-UP RESISTOR REGISTER
#define INTF 0x07 // INTERRUPT FLAG REGISTER
#define INTCAP 0x08 // INTERRUPT CAPTURED VALUE FOR PORT REGISTER
#define GPIO 0x09 // GENERAL PURPOSE I/O PORT REGISTER
#define OLAT 0x0A // OUTPUT LATCH REGISTER 0

// setup for MySensors
#define MY_NODE_ID 30
//#define MY_DEBUG // comment out this line to remove MySensors use of serial port!!!
#define SERIAL_TEST true // d0 and d1 can not be used if the serial bus is active!!!

#define MY_PARENT_NODE_ID 0
#define MY_PARENT_NODE_IS_STATIC

// Enable and select radio type attached 
#define MY_RADIO_RF24
#define MY_RF24_PA_LEVEL  RF24_PA_LOW

// Set this to the pin you connected the Water Leak Detector's analog pins to
// The Analog pins are used to sense the moisture level
#define AI0_PIN A0
#define AI1_PIN A2
#define AI2_PIN A1
#define AI3_PIN A3
#define AI4_PIN A4
#define AI5_PIN A5
#define AI6_PIN A6
#define AI7_PIN A7

// Arduino output pin setup
#define INTERRUPT_PIN 8 // For MCP23008, pins 8 - 5
#define RESET_PIN 7 
#define SDA_PIN 6
#define SCL_PIN 5
#define POWER_PIN 4 // Sensor Power Pin
#define FLOW_PIN 3 // Flow sensor input pin
#define MCP_PIN5 2 // IRQ for NF24 Radio
#define MCP_PIN6 1 // Currently unused. This pin and the one below will not work in SERIAL_MODE OR MY_DEBUG are true!!!
#define MCP_PIN7 0

// analog inputs
#define CHILD_ID_START_OF_AI 0
#define CHILD_ID_AI0 0
#define CHILD_ID_AI1 1
#define CHILD_ID_AI2 2
#define CHILD_ID_AI3 3
#define CHILD_ID_AI4 4 
#define CHILD_ID_AI5 5
#define CHILD_ID_AI6 6
#define CHILD_ID_AI7 7

// digital outputs (switches in HA)
#define CHILD_ID_START_OF_RELAYS 10
#define CHILD_ID_DO0 10 
#define CHILD_ID_DO1 11
#define CHILD_ID_DO2 12
#define CHILD_ID_DO3 13
#define CHILD_ID_DO4 14
#define CHILD_ID_DO5 15
#define CHILD_ID_DO6 16
#define CHILD_ID_DO7 17

//Auto/Manual Mode Switches
#define CHILD_ID_START_OF_AUTOS 20 
#define CHILD_ID_AutoMan0 20 
#define CHILD_ID_AutoMan1 21
#define CHILD_ID_AutoMan2 22
#define CHILD_ID_AutoMan3 23
#define CHILD_ID_AutoMan4 24
#define CHILD_ID_AutoMan5 25
#define CHILD_ID_AutoMan6 26
#define CHILD_ID_AutoMan7 27

#define CHILD_ID_FLOW 30
#define CHILD_ID_DAY_NIGHT 31 // day night sensor gets data from Home Assistant
#define CHILD_ID_LOW_FLOW 32 // low flow alarm indicator for HA - sends alarm, shuts down system
#define CHILD_ID_OPEN_SENSOR 33 // open sensor alarm indicator for HA - sends alarm, shuts down system
#define CHILD_ID_SAFEFLOW_SWITCH 34 // if there is an automatic shutdown (safeFlow = false), this switch let's the system restart (safeFlow = true)

// remeber that fully dry give 1023 reading
#define MAX_VALVE_TIME 5 // maximum time a valve can stay on in minutes. If moisture level hasn't dropped on next cycle, valve will
                          // turn on againg
#define VALVES_OFF_MOISTURE_MEASUREMENT_TIME 15 // Time in minutes between moisture sensor readings when no valves are open.
#define VALVES_ON_MOISTURE_MEASUREMENT_TIME 0.1 // Time in minutes between moisture sensor readings when a valve is open.

// remember that fully dry gives 1023 reading
// you calculate the values for the following targets from the desired moisture level as follows:
// TARGET = 1024/(Rseries/(151.4*M%^-3.7) + 1), where M% is the fractional moisture level -- 60% = 0.6
// So, for a range of 40% to 60%: (1000 is the value of the series resistor!)
// 1024/(1000/(151.4(.4)^-3.7) + 1) = 837
// 1024/(1000/(151.4(.6)^-3.7) +1) = 512
// If you are not using Aref by connecting the sensor drive signal to Aref, then check the sensor open circuit value for AI
// In my case, that value is 973, so 837*973/1024 = 765 and 512*972/1024 = 486.5
#define TARGET_FULL_MOISTURE 487 // maximum expected reading for fully irrigated soil (soil is wet enough)
#define TARGET_MIN_MOISTURE 837 // minimum expected reading for fully irrigated soil (soil is too dry)
#define NUM_VALVES 6 // the total numbeer of valves (max 8)

#define RELAY_ON 1
#define RELAY_OFF 0
#define K 2.28 // 1380 pulses/liter found online.  Max Flow through 30' should be about 5 GPH or 20 liters/hour or 0.33 liters/min or .0055 liters per sec.  
               // That implies about 8 pulses per second.  Some report closer to 30 Hz?  Our unit should be milliliters per second, so K should be 1.38. 
               // For the sensor used in this project, the reported value K = 1.38 was too small.  Flow (pulsed based) yeilded 73, for 44 ml/sec.
               // In this code, flowRate = count/2K, where counts are made on both rising and falling edges.  Flow rate should equal flowRate/1.65, so
               // Knew = 1.28 * 1.65 or 2.28.

//#define Rseries 1000.00 // series resistance used in moisture measurement
// load libraries

#include <SPI.h>
#include <MySensors.h>
#include <BitBang_I2C.h>

// Start I2C
BBI2C bbi2c;  

// Variables Definitions
uint16_t moisture_Level[NUM_VALVES]; // moisture level is just the binary voltage reading at the analog input.  It's converted to % by Home Assistant.
                                     // Convertion equation: M% = (((((1000.0 / (924 / AnalogReading - 1)))/151.35)^(-0.27))*100)
                                     // where 924 is the maximum open circuit sensor reading.  (on next itteration will tie drive voltage to Vref!
uint16_t oldmoisture_Level[NUM_VALVES] = {0}; // initialize all old data to zero
uint16_t startMoistureLevel = 1024; // used for sensor testing

boolean newLoop = true; // to update HA after power outage
//unsigned long oldNoDataTime = 0; // used to check for no data to force communication with HA
unsigned long oldValveOnTime = 0; // used to control the amount of time a valve is open
unsigned long oldNoMoistureTime = 0; // minutes between moisture measurements when no valve is on

byte AI_pin[] = {AI0_PIN, AI1_PIN, AI2_PIN, AI3_PIN, AI4_PIN, AI5_PIN, AI6_PIN, AI7_PIN};
byte CHILD_ID_AI[] = {CHILD_ID_AI0, CHILD_ID_AI1, CHILD_ID_AI2, CHILD_ID_AI3, CHILD_ID_AI4, CHILD_ID_AI5, CHILD_ID_AI6, CHILD_ID_AI7};
byte CHILD_ID_DO[] = {CHILD_ID_DO0, CHILD_ID_DO1, CHILD_ID_DO2, CHILD_ID_DO3, CHILD_ID_DO4, CHILD_ID_DO5, CHILD_ID_DO6, CHILD_ID_DO7};
byte CHILD_ID_AutoMan[] = {CHILD_ID_AutoMan0, CHILD_ID_AutoMan1, CHILD_ID_AutoMan2, CHILD_ID_AutoMan3, 
     CHILD_ID_AutoMan4, CHILD_ID_AutoMan5, CHILD_ID_AutoMan6, CHILD_ID_AutoMan7};

bool autoMan_State[NUM_VALVES] = {false}; // man if false, auto if true
bool ack = 1; 
float flowRate = 0.0;
//float Rsoil = 0.0;
bool safeFlow = true;  // if flow measures to long, the system will set this flag false and prevent valves from being actuated (prevent over heating)
bool lowFlow = false; // if the flow is too low, the system sets this flag and shuts down.  HA can see this flag.
bool openSensor = false; // if a sensor is open and doesn't responde to irrigation, the system sets this flag and shuts down.  HA can see this flag.
byte flowTestCount = 0; // keeps track of the number of zero flow measurements made - system shuts down after NUM_FLOW_TESTS
bool dayNight = false; // if true, it is daytime and the system should not water plants
uint8_t bitValue[] = {1,2,4,8,16,32,64,128};

// MySensors messages
MyMessage msgAI[NUM_VALVES]; // these messages tell HA the moisture level
MyMessage msgGPIO[NUM_VALVES]; // these messages let HA know what relays
MyMessage msgAutoMan[NUM_VALVES]; // these messages let HA know what relays
MyMessage msgFlow(CHILD_ID_FLOW, V_FLOW);
MyMessage msgDayNight(CHILD_ID_DAY_NIGHT, V_TRIPPED); // used to prevent watering during the day
MyMessage msgLowFlow(CHILD_ID_LOW_FLOW, V_TRIPPED); // used to let HA know that we have no water flow
MyMessage msgOpenSensor(CHILD_ID_OPEN_SENSOR, V_TRIPPED); // used to let HA know that we may have an open sensor
MyMessage msgRestart(CHILD_ID_SAFEFLOW_SWITCH, V_STATUS); // safeMode switch, shut down due to system failure, restart through HA

void setup(){
  // setup MCP23008 for output
  pinMode(RESET_PIN, OUTPUT);
  digitalWrite(RESET_PIN, 1); // reset pin on mcp23008
  pinMode(POWER_PIN, OUTPUT);
  digitalWrite(POWER_PIN, false); // turn off sensor power, power direct from pin here!!!!
  pinMode(INTERRUPT_PIN, INPUT);  
  
  //Setup inputs and outputs
    for (int i = 0; i < NUM_VALVES; i++) {
      pinMode(AI_pin[i], INPUT);
    }
    pinMode(FLOW_PIN, INPUT_PULLUP);  // flow sensor requires the input have a pullup resistor
    
  // initialize messages
  for (int i = 0; i < NUM_VALVES; i++) {
    msgAI[i].sensor = i; // Analog sensors start at child ID 0
    msgAI[i].type = V_LEVEL; // these are the moisture sensors
    msgGPIO[i].sensor = i + 10; // Relays start at child ID 10
    msgGPIO[i].type = V_STATUS; // these are the sprinkler valves
    msgAutoMan[i].sensor = i + 20; // AutoMan switches start at child ID 20
    msgAutoMan[i].type = V_STATUS; // these are the switch to set mode
  }
  
  // I2C initialization
  memset(&bbi2c, 0, sizeof(bbi2c));
  bbi2c.bWire = 0; // use bit bang, not wire library
  bbi2c.iSDA = SDA_PIN;
  bbi2c.iSCL = SCL_PIN;
  I2CInit(&bbi2c, 100000L);
  delay(100); // allow devices to power up

  // I2C ready to go, set up for output
  writeRegister(IODIR, 0); // make all GPIO pins outputs
  writeRegister(IPOL, 0); // make all GPIO pins not inverted
  writeRegister(GPIO, 255); // turn all bits on, all valves off (valves are active low!)
}

void presentation()
{ 
  // Send the sketch version information to the gateway
  sendSketchInfo("IRRIGATION SYSTEM ", VERSION);
  Serial.print("Irrigation System, 2021, Version ");Serial.println(VERSION);  // this line will identify version even when MySensor Debug is turned off.

  // Register all sensors to gw (they will be created as child devices)
  for (int i = 0; i < NUM_VALVES; i++) {
    present(CHILD_ID_AI[i], S_MOISTURE);
    present(CHILD_ID_DO[i], S_SPRINKLER);
    present(CHILD_ID_AutoMan[i], S_LIGHT);
  }
  present(CHILD_ID_FLOW, S_WATER, "Water Flow Rate");
  present(CHILD_ID_DAY_NIGHT, S_DOOR); // used to prevent watering during the day - binary sensor
  present(CHILD_ID_LOW_FLOW, S_DOOR); // used to let HA know that we have no water flow - binary sensor
  present(CHILD_ID_OPEN_SENSOR, S_DOOR); // used to let HA know that we have an open sensor - binary sensor
  present(CHILD_ID_SAFEFLOW_SWITCH, S_LIGHT); // if off, system is idle, if one, system is active

  send(msgRestart.set(false)); 
}

void loop()    
{   
  if (newLoop) { updateAll(); newLoop = false; } // make sure HA is aware of current state after powerdown
                                                 // and collect moisture levels
  if (!dayNight) { // if !dayNight = true, it's night time and good to go
    if (safeFlow) {
      // check time to see if we need a moisture reading - different delay during watering
      if (millis() < oldNoMoistureTime) { oldNoMoistureTime = 0; }  // millis() can roll over making it smaller than oldNoDataTime
      if ((millis()- oldNoMoistureTime) > ((isAnyValveOn()?1:0)*VALVES_ON_MOISTURE_MEASUREMENT_TIME + 
                                          (isAnyValveOn()?0:1)*VALVES_OFF_MOISTURE_MEASUREMENT_TIME) * 60000) { // send data to HA to let it know where still alive
        oldNoMoistureTime = millis();  // update time
        newLoop = true;  // forces an update to HA
        readMoisture();  // reads all sensors
        flowRate = flowMeasurement(); // this is not the only place where a flowrate measurement is made; check getLastFlowRate() - used when closing valves
      } 
      // open and close valves automatically when set by autoMan_State and send moisture readings to HA when appropriate
      // valves are turned on and off manually through the receive() function!!
      for (int i = 0; i < NUM_VALVES; i++) {
        if (abs(moisture_Level[i] - oldmoisture_Level[i]) > 50 ) { // only send data upon change of state
          send(msgAI[i].set(moisture_Level[i],1)); // will automatically send all moisture_levels on first newLoop
          oldmoisture_Level[i] = moisture_Level[i];
        }
        if (autoMan_State[i] == true) { // must be in auto mode to change valve state
          if ((moisture_Level[i] < TARGET_FULL_MOISTURE) && valveState(i) == true) {
            writeRegister(GPIO, 255); // turn all bits on, all valves off (valves are active low!)
            send(msgGPIO[i].set(valveState(i)));
            getLastFlowRate();  // valves are closed, make sure flow has stopped
          }
          if ((moisture_Level[i] > TARGET_MIN_MOISTURE) && !isAnyValveOn()) { // only turn on if all other valves are off
            writeNotGPIO(i, true); // turn on water (valves are active low, but writeNotGPIO does inversion)
            send(msgGPIO[i].set(valveState(i)));
            startMoistureLevel = moisture_Level[i]; // save for sensor check below
            oldValveOnTime = millis();  // set start time for valve[i] on duration.  only one valve can be on at a time, so we need only one oldValveOnTime!           
          }
        }  
      }
      // Check flow and moisture response if valve is on
      if (isAnyValveOn() == true) { // one of the valves is on, let's check to see if moisture sensor and the flow meter are responding
        if (millis() < oldValveOnTime) { oldValveOnTime = 0; }  // millis() can roll over making it smaller than oldNoDataTime            
        if ((millis()- oldValveOnTime) > MAX_VALVE_TIME * 60000) { // time to turn off the valve to prevent over watering
          if (flowRate < 5.0) { // oops low flow
            lowFlow = true;
            send(msgOpenSensor.set(true)); // let HA know the system is shutting down due to an open sensor
            safeFlowShutdown();
          }
          else if(startMoistureLevel >= oldmoisture_Level[whichValveIsOn()] ) { // if the measured moisture level hasn't dropped
            openSensor = true;
            send(msgLowFlow.set(true)); // send alarm to HA to indicate system shut down.             
            safeFlowShutdown(); // shutdown system and let HA know valves are all off 
          }
        }
      }
      else { oldValveOnTime = millis(); } // resets every loop cycle if no valve is on
    }
  }
}

void receive(const MyMessage &message) {
  byte relayPinIndex;
  
  if (message.isAck()) {
     // if (SERIAL_TEST) {Serial.println("This is an ack from gateway");}
  }
  if (message.type == V_STATUS) { // possible sensors are:
                                  //  Digital IO -> 10 to 17
                                  //  AutoMan Switches -> 20 - 27
                                  //  SafeFlow Switch -> 34
    if (message.sensor < 18 && message.sensor > 9) { // must be a relay
      // Change relay state
      // Calculate relay from sensor number
      relayPinIndex = message.sensor - CHILD_ID_START_OF_RELAYS; // relayPinIndex[0] thru relayPinIndex[7]
      if (!autoMan_State[relayPinIndex] && safeFlow) { // only change relay state if in manual mode and safeFlow
        writeNotGPIO(relayPinIndex, message.getBool()); // turns off all valves and sets state of valve(relayPinIndex) true or false
        if(!message.getBool()) getLastFlowRate(); // make sure we get a flow measurement after valves are turned off
        for (int i = 0; i < NUM_VALVES; i++) { // set all valveStates except valveState(relayPinIndx) to false.
            send(msgGPIO[i].set(valveState(i)));
        }
      }
      else if(!safeFlow) {
        for (int i = 0; i < NUM_VALVES; i++) { // turn off all valves
          writeNotGPIO(i, false); // turn off all valves
          send(msgGPIO[i].set(false)); // don't know why this is necessary
        }
        getLastFlowRate(); // make sure we get a flow measurement after valves are turned off
      }
    }
    else if (message.sensor < 28 && message.sensor > 19){ // must be an AutoMan Switch
      autoMan_State[message.sensor - 20] = message.getBool(); // this means state was changed by HASS
    }
    else if (message.sensor == 34) { // HA requesting SafeFlow reset
      if(message.getBool() == true) {
        safeFlow = true; // user can only turn switch on.  here it's turned off again after one second.
        lowFlow = false;
        openSensor = false;
        delay(1000);
        send(msgRestart.set(false)); // turn off the HA switch
        oldValveOnTime = millis(); 
      }    
    }
  }
  if (message.type == V_TRIPPED) { // recieved dayNight state from HA
    if (message.sensor == 31) { // this is the day night switch that HA sends to prevent daytime watering
        dayNight = message.getBool(); // if true, it's daytime, do not water
    }
  }
}

// Update All
void updateAll()
{
  for (int i = 0; i < NUM_VALVES; i++) {
    send(msgGPIO[i].set(valveState(i)));
    send(msgAI[i].set(moisture_Level[i],1));
    oldmoisture_Level[i] = moisture_Level[i];
    send(msgAutoMan[i].set(autoMan_State[i]));
  }
  send(msgFlow.set(flowRate,2));
  send(msgLowFlow.set(lowFlow)); // used to let HA know that we have no water flow
  send(msgOpenSensor.set(openSensor)); // used to let HA know that we may have an open sensor
}

bool isAnyValveOn() { 
  bool result = true;

  if(readRegister(GPIO) == 255 ) {result = false;}
  // Serial.print("isAny = ");Serial.println(result);Serial.print("GPIO = ");Serial.println(readRegister(GPIO));
  return(result);
}

bool valveState(uint8_t whichBit) {
  return(!bitRead(readRegister(GPIO), whichBit));
}

byte whichValveIsOn() {
  for (byte i = 0; i < NUM_VALVES; i++) {
    if(valveState(i)) {return(i);}
  }
}

void readMoisture() {
  // read all the moisture levels, but don't send to HA
  digitalWrite(POWER_PIN, true); // Turn on sensor power; powers all sensors; active low
  delay(10); //delay 10 milliseconds to allow reading to settle - determined by testing
  for (int i = 0; i < NUM_VALVES; i++) { // read all sensors
    moisture_Level[i] = analogRead(AI_pin[i]);  // update moisture levels
  } 
  digitalWrite(POWER_PIN, false); // turn power off to sensors again
}

float flowMeasurement() { // take a second to check flow rate
                          // this is a crude method used here because there are no interrupt pins left
                          // in this implementation.  At the max reported flow rate through 1/4" drip
                          // tubing 0f 20 GPH, we can anticipate at pulse frequency of 30 Hz.  That's
                          // slow enough to make this routine work well.
 
  bool state = digitalRead(FLOW_PIN);
  bool oldState = state;
  bool notDone = true;
  unsigned long int count = 0;
  unsigned long int oldMillis = millis();
  
  while (notDone) {
    state = digitalRead(FLOW_PIN);
    if (state != oldState) {
      oldState = state;
      count++;      
    }
    if( oldMillis > millis()) {oldMillis = 0;} // rollover event
    notDone = (millis() - oldMillis < 1000); // 1000 = 1 sec: when this is false, we are done
  }
  flowRate = count/(2*K); // gets two counts per square wave; but rising and falling!
  return(flowRate); // K is the pulses per liter (1380), so we are returning the flow rate in liters per second
                   // Should be 0.022 liters per second or there abouts.
}

void getLastFlowRate() {
  delay(2000); // delay to let valve close and flow rate to settle
  flowRate = flowMeasurement(); // this takes one second to execute
  send(msgFlow.set(flowRate, 2)); // Update HA after valves have closed.  Should be zero, but it no, there's a problem.
}

uint8_t readRegister(uint8_t regAddr) {
  uint8_t Data;
  uint8_t *pu8Data = &Data;
  
  I2CReadRegister(&bbi2c, MCP23008_ADDR, regAddr, pu8Data, 1);
  return(Data);
}

void writeRegister(uint8_t regAddr, uint8_t data) {
  uint8_t Data[2] = {regAddr, data};
  uint8_t *pu8Data;
  
  pu8Data = &Data[0];
  I2CWrite(&bbi2c, MCP23008_ADDR, pu8Data, 2); // write both the register addr and the data
}

void writeNotGPIO(uint8_t pin, bool state) { // set particular pin true or false (only one bit true at a time!!!
  uint8_t newState;

  writeRegister(GPIO, 255); // turn all bits on, all valves off
  if(state) {
    newState = ~bitValue[pin]; // inverts the binary number
    writeRegister(GPIO, newState);
  }
}

void safeFlowShutdown() {
  safeFlow = false; // system shuts down until attended to.  When repaired, turn system off and on again.
  writeRegister(GPIO, 255); // turn all bits on, all valves off (valves are active low!)
  for (int i = 0; i < NUM_VALVES; i++) {
    send(msgGPIO[i].set(valveState(i)));
  }
  getLastFlowRate(); // make sure flow has shut down.
  send(msgRestart.set(false)); // let HA know that we have a problem - this is a switch in HA
}

MEGA Irrigaton System with Display 1.3 (obsolete)

C/C++
No preview (download only).

HA Template Sensors (Nano System)

YAML
These template sensors were created to convert raw analog input data into moisture percent. For this system, there is no temperature compensation. Even so, the system will still do a good job of keeping plants watered.
- platform: template
  sensors:
    moisture_0:
      friendly_name: Moisture 0
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_0') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_1:
      friendly_name: Moisture 1
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_1') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_2:
      friendly_name: Moisture 2
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_2') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_3:
      friendly_name: Moisture 3
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_3') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_4:
      friendly_name: Moisture 4
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_4') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_5:
      friendly_name: Moisture 5
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_5') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"

Template Sensors (Nano System)

YAML
- platform: template
  sensors:
    moisture_0:
      friendly_name: Moisture 0
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_0') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_1:
      friendly_name: Moisture 1
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_1') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_2:
      friendly_name: Moisture 2
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_2') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_3:
      friendly_name: Moisture 3
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_3') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_4:
      friendly_name: Moisture 4
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_4') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"
    moisture_5:
      friendly_name: Moisture 5
      unit_of_measurement: "%"
      value_template: "{{ (((((1000.0 / (973 / (states('sensor.irrigation_system_30_5') | float) - 1)))/151.35)**(-0.27))*100) | round(1) }}"

HA Lovelace File (Nano System)

YAML
UI-Lovelace.yaml
  - title: Irrigation System
    cards:
      - type: vertical-stack
        title: Controls
        cards:
          - type: entities
            title: Water Valves
            show_header_toggle: false
            entities:
            - entity: switch.irrigation_system_30_10
              name: Railing 1 Valve
            - entity: switch.irrigation_system_30_11
              name: Hanging 1 Valve
            - entity: switch.irrigation_system_30_12
              name: Railing 2 Valve          
            - entity: switch.irrigation_system_30_13
              name: Hanging 2 Valve 
            - entity: switch.irrigation_system_30_14
              name: Tomato 1 Valve 
            - entity: switch.irrigation_system_30_15
              name: Tomato 2 Valve 
          - type: entities
            title: Manual (off), Auto(on))
            show_header_toggle: false
            entities:
            - entity: switch.irrigation_system_30_20
              name: Railing 1 Valve
            - entity: switch.irrigation_system_30_21
              name: Hanging 1 Valve
            - entity: switch.irrigation_system_30_22
              name: Railing 2 Valve          
            - entity: switch.irrigation_system_30_23
              name: Hanging 2 Valve
            - entity: switch.irrigation_system_30_24
              name: Tomato 1 Valve
            - entity: switch.irrigation_system_30_25
              name: Tomato 2 Valve
          - type: entities
            title: Manual (off), Auto(on))
            show_header_toggle: false
            entities:
            - entity: binary_sensor.irrigation_system_30_31
              name: Day/Night
            - entity: binary_sensor.irrigation_system_30_32
              name: Low Flow Error
              device_class: safety
            - entity: binary_sensor.irrigation_system_30_33
              name: Open Sensor Error
            - entity: switch.irrigation_system_30_34
              name: System Restart
      - type: vertical-stack
        title: Moisture Sensors Gauges
        cards:
          - type: gauge
            entity: sensor.moisture_0
            name: Railing 1 Moisture
            unit: wt%
          - type: gauge
            entity: sensor.moisture_1
            name: Hanging 1 Moisture
            unit: wt%
          - type: gauge
            entity: sensor.moisture_2
            name: Railing 2 Moisture
            unit: wt%
          - type: gauge
            entity: sensor.moisture_3
            name: Hanging 2 Moisture
            unit: wt%
          - type: gauge
            entity: sensor.moisture_4
            name: Floor 1 Moisture
            unit: wt%
          - type: gauge
            entity: sensor.moisture_5
            name: Floor 2 Moisture
            unit: wt%
          - type: gauge
            entity: sensor.irrigation_system_30_30
            name: Water Flow Rate
            unit: ml/sec
          - type: history-graph
            title: Moisture Sensors Graphs
            hours_to_show: 12
            entities:
              - entity: sensor.moisture_0
                name: Railing 1 Moisture
              - entity: sensor.moisture_1
                name: Hanging 1 Moisture
              - entity: sensor.moisture_2
                name: Railing 2 Moisture
              - entity: sensor.moisture_3
                name: Hanging 2 Moisture  
              - entity: sensor.moisture_4
                name: Floor 1 Moisture
              - entity: sensor.moisture_5
                name: Floor 2 Moisture
          - type: history-graph
            title: Raw Moisture Sensors Graphs
            hours_to_show: 12
            entities:
              - entity: sensor.irrigation_system_30_0
                name: Railing 1 Moisture
                unit_of_measure: C
              - entity: sensor.irrigation_system_30_1
                name: Hanging 1 Moisture
              - entity: sensor.irrigation_system_30_2
                name: Railing 2 Moisture
              - entity: sensor.irrigation_system_30_3
                name: Hanging 2 Moisture
              - entity: sensor.irrigation_system_30_4
                name: Floor 1 Moisture
              - entity: sensor.irrigation_system_30_5
                name: Floor 2 Moisture 
                

HA Automation File (Nano)

YAML
  - alias: "Irrigation Day"
  - alias: "Irrigation Day"
    trigger:
      platform: sun
      event: sunrise
      offset: "3:00:00"
    action:
      service: python_script.set_state
      data_template:
        entity_id: binary_sensor.irrigation_system_30_31
        state: 'on'
      
  - alias: "Irrigation Night"
    trigger:
      platform: sun
      event: sunset
      offset: "-3:00:00"
    action:
      service: python_script.set_state
      data_template:
        entity_id: binary_sensor.irrigation_system_30_31
        state: 'off' 
   
      
  - alias: "Irrigation Flow Failure Alert"
    trigger:
    - platform: state
      entity_id: binary_sensor.irrigation_system_20_32
      to: "on"
    action:
    - service: notify.gmail
      data:
        message: "Sharon Irrigation Flow Failure"
        title: "Irrigation Alert"
        
  - alias: "Irrigation Sensor Failure Alert"
    trigger:
    - platform: state
      entity_id: binary_sensor.irrigation_system_20_33
      to: "on"
    action:
    - service: notify.gmail
      data:
        message: "Sharon Irrigation Sensor Failure"
        title: "Irrigation Alert"

HA Customize File (Nano System)

YAML
binary_sensor.irrigation_system_30_32:
  friendly_name: Low Flow Error
  device_class: safety
binary_sensor.irrigation_system_30_31:
  friendly_name: Day/Night
  device_class: light
  entity_picture: /local/day-and-night-icon.png
binary_sensor.irrigation_system_30_33:
  friendly_name: Open Sensor
  device_class: safety

HA Python Scripts (Nano System)

YAML
/config/python_scripts/set_state.py
# by Rod Payne 

inputEntity = data.get('entity_id')
if inputEntity is None:
    logger.warning("===== entity_id is required if you want to set something.")
elif hass.states.get(inputEntity) is None:
    logger.warning("===== unknown entity_id: %s", inputEntity)
else:
    inputStateObject = hass.states.get(inputEntity)
    inputState = inputStateObject.state
    inputAttributesObject = inputStateObject.attributes.copy()

    for item in data:
        newAttribute = data.get(item)
        logger.debug("===== item = {0}; value = {1}".format(item,newAttribute))
        if item == 'entity_id':
            continue            # already handled
        elif item == 'state':
            inputState = newAttribute
        else:
            inputAttributesObject[item] = newAttribute

    hass.states.set(inputEntity, inputState, inputAttributesObject)

(obsolete)

C/C++
No preview (download only).

(obsolete)

C/C++
No preview (download only).

(obsolete)

C/C++
No preview (download only).

MEGA Irrigation_System_w_Display_1.3_w_Mysensors_w_Drive_Board2.30.ino

C/C++
I've added a precomiler #define called MY_MYSENSORS. If this line of code is defined, then MySensors will be compiled with the code. If not, MySensors will be left out and the system will compile with the display functionality, but without the MySensors interface to your home automation system.
#define PROGRAM "Irrigation System w/Display 1.3 w/Drive_Board"
#define VERSION "version 2.30"
/* MEGA Irrigation System w Display w Mysensors
 *  P. Zavracky, (c) 2021
/* REVISION HISTORY
 *  Written by Paul M. Zavracky (C) 2021
 *  Borrows heavily from the work of zillions of others
 *  This is an upgrade of the original Nano version (2.95)
 *  
 *  The irrigation system comprises a set of 1 to 8 1/4 12v water valves, a moisture sensor, an arduino, 
 *  an NRF24 Radio, and 8 drivers.  The Arduino takes both the digital and analog signals from the 
 *  moisture sensor and uses this information to determine if watering is needed.  If so, the Arduino
 *  sends a signal to the driver board, actualing the appropriate valve.  The driver connects a 12V supply
 *  to the water valve.  The Arduino continues monitoring the moisture sensor.  Once a predetermined level
 *  is reached, the Arduino turns off the water flow.
 *  
 *  This version adds the drive board.  That means that instead of active low drivers, we now have active high 
 *  transistor drivers.  We also have a shutoff driver for the shutoff valve.  Therefore, system leak detection 
 *  is added and the shutoff valve must be actuated whenever any valve is on and turned off (except when
 *  conducting a leak test) when no valves are on.
 *  
 *  In this scheme, the routine 'writePORTA' which originally inverted the port data byte, now does not!  So,
 *  the name carried over no longer accurately portrays the routines function.  Therefore the routine is renamed to
 *  writePORTA.
 *  
 *  Added in this iteration is a leak check of the plumbing between the shutoff valve and the zone valves.  This region
 *  has a significant number of fittings that could develop leaks.  It is also a region, that without a shutoff valve 
 *  would continue to leak as long as the system is running.  So, the shutoff valve removes pressure from this area, 
 *  however, without some kind of leak check, a catastrophic failure of the plumbing would pour water out each time a 
 *  zone is activated.  To prevent this from happening, periodic leak checks are conducted.  If a leak is discovered,
 *  the system will shut down and Home Assistant will send an appropriate message.
 *  
 *  This code now uses the precompiler name MY_MYSENSORS which is #defined at the beginning of the code.  If you
 *  comment this line out, MySensors will be eliminated from the compilation and you can use the system with the display
 *  only.
*/


// setup for MySensors
#define MY_NODE_ID 41
#define MY_DEBUG // comment out this line to remove MySensors use of serial port!!!
#define MY_MYSENSORS // comment out this line to remove MySensors altogether

#define MY_PARENT_NODE_ID 0
#define MY_PARENT_NODE_IS_STATIC

// Enable and select radio type attached 
#define MY_RADIO_RF24
#define MY_RF24_PA_LEVEL  RF24_PA_MAX
// RF24_PA_MIN = -18dBm
// RF24_PA_LOW = -12dBm
// RF24_PA_HIGH = -6dBm
// RF24_PA_MAX = 0dBm

// Specifiaclly for MEGA
#define MY_RF24_CE_PIN 11
#define MY_RF24_CS_PIN 12

// analog inputs
#define CHILD_ID_START_OF_AI 0 // the below AI IDs allow rearrangement of sensors so that during installation, they may be properly coupled to valves
#define CHILD_ID_AI0 0
#define CHILD_ID_AI1 1
#define CHILD_ID_AI2 2
#define CHILD_ID_AI3 3
#define CHILD_ID_AI4 4 
#define CHILD_ID_AI5 5
#define CHILD_ID_AI6 6
#define CHILD_ID_AI7 7

// digital outputs (switches in HA)
#define CHILD_ID_START_OF_VALVES 10

//oneWire Temperature Sensors
#define CHILD_ID_START_OF_TEMPS 20 

//Auto/Manual Mode Switches
#define CHILD_ID_START_OF_AUTOS 30 

#define CHILD_ID_FLOW 40
#define CHILD_ID_DAY_NIGHT 41 // day night sensor gets data from Home Assistant
#define CHILD_ID_LOW_FLOW 42 // low flow alarm indicator for HA - sends alarm, shuts down system
#define CHILD_ID_UNRESPONSIVE_SENSOR 43 // open sensor alarm indicator for HA - sends alarm, shuts down system
#define CHILD_ID_SAFEFLOW_SWITCH 44 // if there is an automatic shutdown (safeFlow = false), this switch let's the system restart (safeFlow = true)
#define CHILD_ID_LEAK_DETECTED 45 // used to alert HA of a leak.  This has saved me from disaster.

#define CHILD_ID_START_OF_TEMP_STATES 80 // keeps track of the condition of the temperature sensors (there might be 8 of these CHILD_IDs)
#define CHILD_ID_START_OF_MOISTURE_OPEN_STATES 90 // keeps track of the condition of the moisture sensors (there might be 8 of these CHILD_IDs)
#define CHILD_ID_START_OF_MOISTURE_SHORT_STATES 100 // open circuit or shorted

// Display and Touchscreen Parameters
#define TFT_CS 48
#define TFT_RST 44
#define TFT_CD 46
#define T_CS 42

// The Analog pins are used to sense the moisture level
#define AI0_PIN 54
#define AI1_PIN 55
#define AI2_PIN 56
#define AI3_PIN 57
#define AI4_PIN 58
#define AI5_PIN 59
#define AI6_PIN 60
#define AI7_PIN 61

#define MENUHEIGHT 20
#define MENUWIDTH 80
#define LABLE0 "OPERATE"
#define LABLE1 "ALARMS"
#define LABLE2 "SET PTS"
#define LABLE3 VERSION

// Arduino output pin setup
#define TMPS0 2 // This is the first of three bits for selecting the eight analog switches connecting single Dallas temp sensors to the one wire temp input (TEMP0_PIN)
#define TMPS1 3 // see below definition of variable tempSensorConfig[]
#define TMPS2 4
#define TEMP0_PIN 5 // this is one of two pins for temperature input.  This one goes to the analog switch between 8 different sensors
#define FLOW_PIN 6 // Flow sensor input pin
#define LED_PIN 8 // LED backlight control pin
#define POWER_PIN 10 // Sensor Power Pin
#define TEMP1_PIN 13 // Temperature oneWire pin (also defined for oneWire below)
#define GATE 47 // must be turned on for outputs to fire!
#define SHUTOFF_VALVE 49 // Safety shutoff valve

#define NUM_VALVES 8 // number of valves in use - up to eight
#define TOUCH_TIME 300 // time in milliseconds between touch readings
#define BASE_EEPROM_ADDR 100 // starting address of data in eeprom.  must leave room for other lib uses

#define ONE_WIRE_BUS TEMP0_PIN // Pin where dallas sensors are connected

#define K 2.28 // 1380 pulses/liter found online.  Max Flow through 30' should be about 5 GPH or 20 liters/hour or 0.33 liters/min or .0055 liters per sec.  
// That implies about 8 pulses per second.  Some report closer to 30 Hz?  Our unit should be milliliters per second, so K should be 1.38.
// For the sensor used in this project, the reported value K = 1.38 was too small.  Flow (pulsed based) yeilded 73, for 44 ml/sec.
// In this code, flowRate = count/2K, where counts are made on both rising and falling edges.  Flow rate should equal flowRate/1.65, so
// Knew = 1.28 * 1.65 or 2.28.

#define FLOW_MOIST_TEST_TIME 5 // the time in minutes a valve can stay on before conducting a flow and moisture variation measurement
                               // This is only done once, because the system will shutdown anyway at MAX_VALVE_TIME
#define MAX_VALVE_TIME 20 // maximum time in minutes a valve can stay on in minutes. If moisture level hasn't dropped on next cycle, valve will
// turn on againg
#define MAX_LED_TIME 5 // maximum time in minutes the LED backlight stays on without a touch
#define VALVES_OFF_MOISTURE_MEASUREMENT_TIME 15 // Time in minutes between moisture sensor readings when no valves are open.
#define VALVES_ON_MOISTURE_MEASUREMENT_TIME 0.1 // Time in minutes between moisture sensor readings when a valve is open.
#define LEAK_CHECK_TIME 60 // time between leakchecks
#define LEAK_DURATION_TIME 30 // basically the delay time in seconds between turning on the shutoff valve and making a flow measurement.  This allows the initial
                              // pressure pulse to settle down before making the leak test.
#define DOT_TIME 1 // time in seconds between dots printed as system cycles through main loop

#define Rseries 1000.00 // series resistance used in moisture measurement

#include <Arduino.h>
#include <SPI.h>
#ifdef MY_MYSENSORS
  #include <MySensors.h> 
#endif
#include "SimpleILI9341.h"
#include <avr/pgmspace.h>
#include <EEPROM.h>
#include <DallasTemperature.h>
#include <OneWire.h>

// start Dallas Temp Sensors
OneWire oneWire(ONE_WIRE_BUS); // Setup a oneWire instance to communicate with any OneWire devices (not just Maxim/Dallas temperature ICs)
DallasTemperature sensors(&oneWire); // Pass the oneWire reference to Dallas Temperature.
// Addresses of DS18B20 sensors connected to the 1-Wire bus are not needed.  This system uses an analog multiplexer to select a particular device
// The multiplexer (74HC4051) outputs are routed in a convenient layout format.  But this format lead to the following configuration of connectors:
// [ 2 ] [ 4 ]
// [ 1 ] [ 6 ]
// [ 0 ] [ 7 ]
// [ 3 ] [ 5 ]
// The preferred order might be 
// [ 0 ] [ 1 ]
// [ 2 ] [ 3 ]
// [ 4 ] [ 5 ]
// [ 6 ] [ 7 ]
// The following variable is used to make this translation.  Therefore, when connecting to the board, your sensors labled S0...S7 are connected to the
// positions using the preferred order.
byte tempSensorConfig[] = {2,4,1,6,0,7,3,5};  // so tempSensorConfig[0] will translate to an index of 2

// variables for Mysensors

byte AI_pin[] = {AI0_PIN, AI1_PIN, AI2_PIN, AI3_PIN, AI4_PIN, AI5_PIN, AI6_PIN, AI7_PIN};
byte CHILD_ID_AI[] = {CHILD_ID_AI0, CHILD_ID_AI1, CHILD_ID_AI2, CHILD_ID_AI3, CHILD_ID_AI4, CHILD_ID_AI5, CHILD_ID_AI6, CHILD_ID_AI7};

bool ack = 1; 


// Variables Definitions
boolean newLoop = true; // to update HA after power outage
unsigned long oldValveOnTime = 0; // used to control the amount of time a valve is open
unsigned long oldNoMoistureTime = 0; // minutes between moisture measurements when no valve is on
unsigned long oldLEDTime = 0; // start time for LED backlight on time
unsigned long oldLeakCheckTime = 0; // used to control amount of time between leak checks
unsigned long oldLeakDurationTime = 0; // used to avoid the pressure pulse delay that ensues when opening the shutoff valve
unsigned long oldDotTime = 0; // system will print a dot each 

byte currentscreen;

bool autoManState[NUM_VALVES]; // man if false, auto if true
bool tempState[NUM_VALVES]; // used to keep track of functional temperature sensors
bool moistureOpenState[NUM_VALVES]; // tracks open sensors
bool moistureShortState[NUM_VALVES]; // tracks shorted sensors
bool lowFlow = false; // if the flow is too low, the system sets this flag and shuts down.  HA can see this flag.
bool unresponsiveSensor = false; // if a sensor is open and doesn't responde to irrigation, the system sets this flag and shuts down.  HA can see this flag.
bool leakDetected = false; // check flow rate when no valves are open and check for leaks.
bool systemSafe = true;
bool leakCheckFlag = false; // this flag is used to initiate a system leak check
float flowRate = 5.0; // just set arbitrary initial flow rate.  This will clear on first cycle through loop

// Update variables
bool oldValveState[NUM_VALVES];
float oldTemp[NUM_VALVES];
float oldMoistureLevel[NUM_VALVES] = {0.0}; // initialize all old data to zero
bool oldAutoManState[NUM_VALVES]; // used in update all to prevent sending repetitive information
bool oldTempState[NUM_VALVES];  // change of state forces update!!
bool oldMoistureOpenState[NUM_VALVES];
bool oldMoistureShortState[NUM_VALVES];
bool oldLowFlow = true;
bool oldUnresponsiveSensor = true;
bool oldLeakDetected = true;
bool oldSystemSafe = true;
float oldFlowRate = 1.0;

uint8_t bitValue[] = {1, 2, 4, 8, 16, 32, 64, 128};

bool safeFlow = true;  // if flow measures to long, the system will set this flag false and prevent valves from being actuated (prevent over heating)
byte flowTestCount = 0; // keeps track of the number of zero flow measurements made - system shuts down after NUM_FLOW_TESTS
bool dayNight = false; // if true, it is daytime and the system should not water plants. This variable can only be changed by MySensors.
float temp[NUM_VALVES];
float moistureLevel[NUM_VALVES];
float startMoistureLevel = 0.0; // used for sensor testing
byte currentScreen = 0;
byte oldCurrentScreen = 0;
bool firstTime = true;
bool startup = true; // used to send HA message once on startup
byte sensor = 0; // this is just for test purposes
byte tempSensorCount = 0; // number of functioning temperature sensors
byte upperMoistureLevel[NUM_VALVES];
byte lowerMoistureLevel[NUM_VALVES];
unsigned long int lastTouchTime = millis();
uint16_t color;
byte dotCounter = 0; // counts the dots printed for each line and occasionally prints a line feed.

// Dallas Temp Sensor Variables
bool metric = false;

#ifdef MY_MYSENSORS
  // MySensors messages
  MyMessage msgAI[NUM_VALVES]; // these messages tell HA the moisture level
  MyMessage msgPORTA[NUM_VALVES]; // these messages let HA know what drivers
  MyMessage msgTemp[NUM_VALVES]; // these messages let HA know the temperature
  MyMessage msgAutoMan[NUM_VALVES]; // these messages let HA know what drivers
  MyMessage msgTempState[NUM_VALVES]; // these messages let HA know about the condition of the temperature sensors (working/not-working)
  MyMessage msgMoistureOpenState[NUM_VALVES]; // these messages let HA know about the condition of the moisture sensors (working/not-working)
  MyMessage msgMoistureShortState[NUM_VALVES];                                        
  MyMessage msgFlow(CHILD_ID_FLOW, V_FLOW);
  MyMessage msgDayNight(CHILD_ID_DAY_NIGHT, V_TRIPPED); // used to prevent watering during the day
  MyMessage msgLowFlow(CHILD_ID_LOW_FLOW, V_TRIPPED); // used to let HA know that we have no water flow
  MyMessage msgOpenSensor(CHILD_ID_UNRESPONSIVE_SENSOR, V_TRIPPED); // used to let HA know that we have an unresponsive sensor
  MyMessage msgLeakDetected(CHILD_ID_LEAK_DETECTED, V_TRIPPED); // system monitors flow sensor even when no valve is on.  If flow is indicated, must be a leak!
  MyMessage msgRestart(CHILD_ID_SAFEFLOW_SWITCH, V_STATUS); // safeMode switch, shut down due to system failure, restart through HA
#endif

void setup(void) {
  Serial.begin(115200);
  Serial.print(PROGRAM);Serial.println(VERSION);
    
  ILI9341Begin(48, 46, 44, 320, 240, ILI9341_Rotation3);
  BeginTouch(42, 3);

  //analogReference(EXTERNAL); // use this command if you're going to use the switched supply as the reference.  Not necessary.
  // set initial array values
  for (int i = 0; i < NUM_VALVES; i++) {
    autoManState[i] = false; // man if false, auto if true
    tempState[i] = false; // used to keep track of functional temperature sensors
    moistureOpenState[i] = false; // tracks open sensors
    moistureShortState[i] = false; // tracks shorted sensors
    oldValveState[i] = true; // forces HA update
    oldTemp[i] = 0.0;
    oldMoistureLevel[i] = 0.0; // initialize all old data to zero
    oldAutoManState[i] = true; // used in update all to prevent sending repetitive information
    oldTempState[i] = false;  // change of state forces update!!
    oldMoistureOpenState[i] = false;
    oldMoistureShortState[i] = false;
  }

  //Setup inputs and outputs
  pinMode(TMPS0, OUTPUT); // these are for the temperature sensors
  pinMode(TMPS1, OUTPUT);
  pinMode(TMPS2, OUTPUT);
  digitalWrite(TMPS0, false); // set for channel zero.  due to board layout considerations, this is actually sensor 4
  digitalWrite(TMPS1, false);
  digitalWrite(TMPS2, false);  
  for (int i = 0; i < NUM_VALVES; i++) {
    pinMode(AI_pin[i], INPUT);
  }
  pinMode(FLOW_PIN, INPUT_PULLUP);  // flow sensor requires the input have a pullup resistor
  pinMode(SHUTOFF_VALVE, OUTPUT);
  pinMode(GATE, OUTPUT);
  digitalWrite(GATE, true); // make sure gate is off to prevent switch inputs to drivers (drivers all off)
  digitalWrite(SHUTOFF_VALVE, false); // make sure SHUTOFF VALVE is off
  pinMode(POWER_PIN, OUTPUT);
  pinMode(LED_PIN, OUTPUT);
  pinMode(30, OUTPUT); // set up power relay pin for output
  // test power pin
  for (int i = 0; i < 3; i++) {
    digitalWrite(POWER_PIN, false); // turn off power to moisture sensors; power pin is true low.
    //digitalWrite(30, false);
    delay(500);
    digitalWrite(POWER_PIN, true);
    //digitalWrite(30, true);
    delay(500);
  }
  digitalWrite(LED_PIN, false); // turn on LED backlight - active low
  oldLEDTime = millis(); // establish on time
  DDRA = B11111111;  // set up Mega PortA for output - these control the valves
  PORTA = 0; // all valves off
  digitalWrite(30, true); // turn on power relay
  digitalWrite(GATE, false); // make sure gate is on to pass switch inputs to drivers

#ifdef MY_MYSENSORS
  // initialize messages for MySensors
    for (int i = 0; i < NUM_VALVES; i++) {
      msgAI[i].sensor = i; // Analog sensors start at child ID 0
      msgAI[i].type = V_LEVEL; // these are the moisture sensors
      msgPORTA[i].sensor = i + CHILD_ID_START_OF_VALVES; 
      msgPORTA[i].type = V_STATUS; // these are the sprinkler valves
      msgTemp[i].sensor = i + CHILD_ID_START_OF_TEMPS; 
      msgTemp[i].type = V_TEMP; // these are the temperature sensors
      msgAutoMan[i].sensor = i + CHILD_ID_START_OF_AUTOS; 
      msgAutoMan[i].type = V_STATUS; // these are the switch to set mode
      msgTempState[i].sensor = i + CHILD_ID_START_OF_TEMP_STATES;
      msgTempState[i].type = V_TRIPPED; // these are binary sensors (S_BINARY)
      msgMoistureOpenState[i].sensor = i + CHILD_ID_START_OF_MOISTURE_OPEN_STATES;
      msgMoistureOpenState[i].type = V_TRIPPED;
      msgMoistureShortState[i].sensor = i + CHILD_ID_START_OF_MOISTURE_SHORT_STATES;
      msgMoistureShortState[i].type = V_TRIPPED; // these are binary sensors (S_BINARY)
    }
#endif

  // get set points from eeprom
  for (int i = 0; i < NUM_VALVES; i++) {
    upperMoistureLevel[i] = EEPROM.read(BASE_EEPROM_ADDR + i);
    lowerMoistureLevel[i] = EEPROM.read(BASE_EEPROM_ADDR + NUM_VALVES + i); // always move the to position of the max number of valves
    if (upperMoistureLevel[i] > 100) {
      upperMoistureLevel[i] = 80; // EEPROM hasn't been writen yet, so use 80 to start.  Will write after updating.
    }
    if (lowerMoistureLevel[i] > 100) {
      lowerMoistureLevel[i] = 40; // EEPROM hasn't been writen yet, so use 40 to start.
    }
  }
  // set up dallas temp sensors
  sensors.begin();

  // display setup
  ClearDisplay(TFT_BLUE);
  DrawBox(0, 0, MENUWIDTH, MENUHEIGHT, TFT_NAVY); // upper lefthand corner location and size of box
  DrawFrame(0, 0, MENUWIDTH, MENUHEIGHT, TFT_WHITE);
  ILI9341SetCursor(15, 15);
  DrawString(LABLE0, SmallFont, TFT_WHITE);
  DrawBox(MENUWIDTH, 0, MENUWIDTH, MENUHEIGHT, TFT_NAVY);
  DrawFrame(MENUWIDTH, 0, MENUWIDTH, MENUHEIGHT, TFT_BLACK);
  ILI9341SetCursor(MENUWIDTH + 15, 15);
  DrawString(LABLE1, SmallFont, TFT_WHITE);
  DrawBox(MENUWIDTH * 2, 0, MENUWIDTH, MENUHEIGHT, TFT_NAVY);
  DrawFrame(MENUWIDTH * 2, 0, MENUWIDTH, MENUHEIGHT, TFT_BLACK);
  ILI9341SetCursor(MENUWIDTH * 2 + 15, 15);
  DrawString(LABLE2, SmallFont, TFT_WHITE);
  DrawBox(MENUWIDTH * 3, 0, MENUWIDTH, MENUHEIGHT, TFT_NAVY);
  DrawFrame(MENUWIDTH * 3, 0, MENUWIDTH, MENUHEIGHT, TFT_BLACK);
  ILI9341SetCursor(MENUWIDTH * 3 + 15, 15);
  DrawString(LABLE3, SmallFont, TFT_WHITE);

  //DrawFrame(0+1, 0+1, MENUWIDTH-2, MENUHEIGHT-2, TFT_WHITE);
}

void presentation()
{ 
  // Send the sketch version information to the gateway
  
  Serial.print("Irrigation System, 2021, Version ");Serial.println(VERSION);  // this line will identify version even when MySensor Debug is turned off.

#ifdef MY_MYSENSORS
  sendSketchInfo("IRRIGATION SYSTEM ", VERSION, true);
  // Register all sensors to gw (they will be created as child devices)
  for (int i = 0; i < NUM_VALVES; i++) {
    present(CHILD_ID_AI[i], S_MOISTURE);
    present(CHILD_ID_START_OF_VALVES + i, S_SPRINKLER);
    present(CHILD_ID_START_OF_TEMPS + i, S_TEMP);
    present(CHILD_ID_START_OF_AUTOS + i, S_LIGHT);
    present(CHILD_ID_START_OF_TEMP_STATES + i, S_DOOR); // indicates when there is no response from sensor
    present(CHILD_ID_START_OF_MOISTURE_OPEN_STATES + i, S_DOOR); // uses AI[] to determine open or short
    present(CHILD_ID_START_OF_MOISTURE_SHORT_STATES + i, S_DOOR);
  }
  present(CHILD_ID_FLOW, S_WATER);
  present(CHILD_ID_DAY_NIGHT, S_DOOR); // used to prevent watering during the day - binary sensor
  present(CHILD_ID_LOW_FLOW, S_DOOR); // used to let HA know that we have no water flow - binary sensor
  present(CHILD_ID_UNRESPONSIVE_SENSOR, S_DOOR); // used to let HA know that we have an open sensor - binary sensor
  present(CHILD_ID_LEAK_DETECTED, S_DOOR); // alert HA of a leak
  present(CHILD_ID_SAFEFLOW_SWITCH, S_LIGHT); // if off, system is idle, if one, system is active
#endif
}

void loop(void) {
  int x, y;

#ifdef MY_MYSENSORS
  if (startup) {
    send(msgRestart.set(false));
    send(msgDayNight.set(true)); // this gets home assistant going
    startup = false; 
  }
#endif
  if (newLoop) {
    readMoistureTemp();  // reads all sensors
    flowRate = flowMeasurement(); // this is not the only place where a flowrate measurement is made; check getLastFlowRate() - used when closing valves 
    updateAllOld(); 
    newLoop = false; } // make sure HA is aware of current state after powerdown
                                                 // and collect moisture levels
  if (!dayNight) { // if !dayNight = true, it's night time and good to go
    if (safeFlow) {
      // check time to see if we need a moisture reading - different delay during watering
      if (millis() < oldNoMoistureTime) {
        oldNoMoistureTime = 0;  // millis() can roll over making it smaller than oldNoDataTime
      }
      if ((millis() - oldNoMoistureTime) > ((isAnyValveOn() ? 1 : 0)*VALVES_ON_MOISTURE_MEASUREMENT_TIME +
                                            (isAnyValveOn() ? 0 : 1)*VALVES_OFF_MOISTURE_MEASUREMENT_TIME) * 60000) { // send data to HA to let it know where still alive
        oldNoMoistureTime = millis();  // update time
        readMoistureTemp();  // reads all sensors
        flowRate = flowMeasurement(); // this is not the only place where a flowrate measurement is made; check getLastFlowRate() - used when closing valves
        if (currentScreen == 0) { updateScreen0(); updateAllOld();} else if (currentScreen == 1) {updateScreen1(); updateAllOld();} // update screens on change of sensor data
      }
      // open and close valves automatically when set by autoManState and send moisture readings to HA when appropriate
      // valves are turned on and off manually through the receive() function or touch screen!!
      for (int i = 0; i < NUM_VALVES; i++) {
        if (abs(moistureLevel[i] - oldMoistureLevel[i]) > 1.0 ) { // only send data upon change of state by more that 1%
#ifdef MY_MYSENSORS          
          send(msgAI[i].set(moistureLevel[i],1)); // will automatically send all moistureLevels on first newLoop
          send(msgTemp[i].set(temp[i],2)); // same here with temps
#endif
          oldMoistureLevel[i] = moistureLevel[i];
          oldTemp[i] = temp[i];
        }
        if (autoManState[i] == true) { // must be in auto mode to change valve state
          if ((moistureLevel[i] > upperMoistureLevel[i]) && valveState(i)) {
            PORTA = 0; // turn all valves off (valves are active low!)
#ifdef MY_MYSENSORS  
            send(msgPORTA[i].set(valveState(i)));
#endif
            getLastFlowRate();  // valves are closed, make sure flow has stopped
          }
          if ((moistureLevel[i] < lowerMoistureLevel[i]) && !isAnyValveOn()) { // only turn on if all other valves are off
            writePORTA(i, true); // turn on water (valves are active low, but writePORTA does inversion)
#ifdef MY_MYSENSORS  
            send(msgPORTA[i].set(valveState(i)));
#endif
            startMoistureLevel = moistureLevel[i]; // save for sensor check below, is sensor responding?
            oldValveOnTime = millis();  // set start time for valve[i] on duration.  only one valve can be on at a time, so we need only one oldValveOnTime!
          }
        }
      }
      // Check flow and moisture response if valve is on
      if (isAnyValveOn() == true) { // one of the valves is on, let's check to see if moisture sensor and the flow meter are responding
        if (millis() < oldValveOnTime) {oldValveOnTime = 0; }  // millis() can roll over making it smaller than oldNoDataTime
        if ((millis() - oldValveOnTime) > FLOW_MOIST_TEST_TIME * 60000) { // time to turn off the valve to prevent over watering
          if (flowRate < 5.0) { // oops low flow
            lowFlow = true;
#ifdef MY_MYSENSORS  
            send(msgLowFlow.set(true)); // send alarm to HA to indicate system shut down.
#endif
            safeFlowShutdown();
          }
          if (startMoistureLevel >= oldMoistureLevel[whichValveIsOn()] + 2 ) { // if the measured moisture level hasn't increased
                                                                               // 2% is added to current reading to overcome noise
            unresponsiveSensor = true;
#ifdef MY_MYSENSORS  
            send(msgOpenSensor.set(true)); // let HA know the system is shutting down due to an open sensor  
#endif           
            safeFlowShutdown(); // shutdown system and let HA know valves are all off
          }
        }
        if ((millis() - oldValveOnTime) > MAX_VALVE_TIME * 60000) {// Even though moisture response and lowflow pass, this valve
                                                                   // has been on too long.  Let's turn if off.
          lowFlow = true; // turn lowFlow and unresponsiveSensor flags on to indicate this failure mode
          unresponsiveSensor = true;
          safeFlowShutdown();
        }
        if (!digitalRead(SHUTOFF_VALVE)) {
          digitalWrite(SHUTOFF_VALVE, true); // turn on water when any other valve is on
          Serial.println();Serial.println("Shut off valve turned on because another valve was turned on");
        } 
      }
      else { // no valves are on, must reset timer and turn off shutoff valve
        oldValveOnTime = millis();  // resets every loop cycle if no valve is on
        if (digitalRead(SHUTOFF_VALVE)) {
          digitalWrite(SHUTOFF_VALVE, false); // shutoff water when no other valves are on
          Serial.println();Serial.println("Shut off valve turned off because no other valve it on");
        }
      }
    }
  }
  // test to see if it's time for a leak check
  if (millis() < oldLeakCheckTime) {oldLeakCheckTime = 0; }  // millis() can roll over making it smaller than oldLeakCheckTime
  if ((millis() - oldLeakCheckTime) > LEAK_CHECK_TIME * 60000) { // let's do a leak check
    oldLeakCheckTime = millis(); // reset time for next cycle
    if (isAnyValveOn() == false) { // ok, no valve is on, we can at least start to conduct a leak test
      if (!digitalRead(SHUTOFF_VALVE)) {
        digitalWrite(SHUTOFF_VALVE, true); // turn on shutoff valve to test for leaks between the supply and the zone valves
        Serial.println();Serial.println("Shut off valve turned on for leak test");
      }
      leakCheckFlag = true; // enables the leak check routine below 
      oldLeakDurationTime = millis(); // start the clock for the next leak check
    }
  }
  // the below code block conducts a leak check after waiting for LEAK_DURATION_TIME.
  if (leakCheckFlag == true) {
    if (isAnyValveOn() == true) { leakCheckFlag = false;} // oops, a valve has been turned on during the leak check.  Abort!!! Wait for next cycle.
    else { // ok, the shutoff valve is open, we need to delay long enough for the pressure pulse to pass, then make a flow measurement
      if (millis() < oldLeakDurationTime) {oldLeakDurationTime = 0; }  // millis() can roll over making it smaller than oldLeakCheckTime
      if ((millis() - oldLeakDurationTime) > LEAK_DURATION_TIME * 1000) { // the pressure pulse delay time has passed, time to check the flow rate  
        // now let's check to make sure that if no valves are on, then no flow is measured.  If it is, we have a leak!
        flowRate = flowMeasurement(); // get the flowrate
        if (flowRate != 0) { // oops, we have a leak
          leakDetected = true;
#ifdef MY_MYSENSORS  
          send(msgLeakDetected.set(false)); delay(500); send(msgLeakDetected.set(true)); // a transition from false to true triggers an automated message from HA to email.
#endif
          oldLeakDetected = leakDetected;
          safeFlowShutdown(); // shutdown system and let HA know valves are all off
        }
        else {
          leakDetected = false;
          leakCheckFlag = false; // we're done here, reset the flag
#ifdef MY_MYSENSORS  
          if (oldLeakDetected != leakDetected) {send(msgLeakDetected.set(leakDetected));} // send message only upon change of state; this triggers on first cycle
#endif
          oldLeakDetected = leakDetected;
        }
        if (digitalRead(SHUTOFF_VALVE)) {
          digitalWrite(SHUTOFF_VALVE, false); // leak test complete, time to turn off the shutoff valve again
          Serial.println();Serial.println("Shut off valve turned off after leak test");
        }
      }
    } 
  }
  
  if (isAnyValveOn() == false && leakCheckFlag == false) { // if all valves off and we are not conducting a leak test,
                                                           // must turn off SHUTOFF_VALVE - necessary for manual op during daylight!
    if (digitalRead(SHUTOFF_VALVE)) {
      digitalWrite(SHUTOFF_VALVE, false); // shutoff water when no other valves are on 
      Serial.println();Serial.println("shutoff closed at end of main loop before display update");
    }
  }
  else if (isAnyValveOn() == true) { 
    if (!digitalRead(SHUTOFF_VALVE)) {
      digitalWrite(SHUTOFF_VALVE, true); 
      Serial.println();Serial.println("shutoff open at end of main loop");
    }
  } // turn on shutoff valve when another valve is on 
  
  // check input from touch screen
  if (GetTouch(&x, &y)) {
    digitalWrite(LED_PIN, false); // display was touched, time to turn on the backlight
    oldLEDTime = millis(); // reset LED backlight on time
    if (y < MENUHEIGHT) { // this is a screen select command
      if (x < 3 * MENUWIDTH) { // touched one of three actionable screen selections
        if (oldCurrentScreen == 2) { // just managed setpoints, must update EEPROM
          for (int i = 0; i < NUM_VALVES; i++) { // error check
            if (lowerMoistureLevel[i] >= upperMoistureLevel[i]) {
              return; // don't change from Screen 2 unless errors are repaired
            }
          }
          for (int i = 0; i < NUM_VALVES; i++) {
            EEPROM.update(BASE_EEPROM_ADDR + i, upperMoistureLevel[i]);
            EEPROM.update(BASE_EEPROM_ADDR + NUM_VALVES + i, lowerMoistureLevel[i]);
          }
        }
        currentScreen = int(x / MENUWIDTH);
        DrawFrame(MENUWIDTH * currentScreen, 0, MENUWIDTH, MENUHEIGHT, TFT_WHITE);
        DrawFrame(MENUWIDTH * oldCurrentScreen, 0, MENUWIDTH, MENUHEIGHT, TFT_BLACK);
        oldCurrentScreen = currentScreen;
        firstTime = true;
      }
      else return; // don't respond to menu 3
    }
  }
  if (currentScreen == 0) {
    if (firstTime) {
      Screen0SetUp();
      firstTime = false;
    }
    if (lastTouchTime > millis()) { lastTouchTime = 0; } // clock rolled over
    if ((millis() - lastTouchTime) > TOUCH_TIME) {
      lastTouchTime = millis();
      if (GetTouch(&x, &y)) {
        byte button = whichButton(x, y);
        if (button == 0) {
          return; // touched screen in non active area
        }
        if (button > 19) { // auto/man buttons
          button = button - 20; // reduce to single digit
          autoManState[button] = !autoManState[button]; // change state
          writePORTA(button, false); // turn off associated valve because we changed auto state on that valve
        }
        else { // must be a valve
          button = button - 10; // reduce to single digit
          if (!autoManState[button]) { // do not turn on valve if in auto state
            if (!valveState(button)) { // if the valve is off, we're going to turn it on
              if (!isAnyAutoValveOn()) { // is a valve in auto state on.  If not, we can turn all valves off and then this valve on.
                PORTA = 0; // turn off all valves
                writePORTA(button, true); // turn on appropriate valve
              }
            }
            else { // the valve is on, and must be the only one on.  Must turn off
              PORTA = 0;
            }
          }
        }
      }
      updateScreen0(); // this is where the screen display is aligned to any state changes above
    }
  }
  if (currentScreen == 1) {
    if (firstTime) {
      Screen1SetUp();
      firstTime = false;
      //Serial.println("finished setup");
    }
    if (lastTouchTime > millis()) { lastTouchTime = 0; } // clock rolled over
    if ((millis() - lastTouchTime) > TOUCH_TIME) {
      lastTouchTime = millis();
      updateScreen1();
    }
  }
  if (currentScreen == 2) {
    if (firstTime) {
      Screen2SetUp();
      firstTime = false;
      //Serial.println("finished setup");
    }
    if (GetTouch(&x, &y)) {
      if (lastTouchTime > millis()) { lastTouchTime = 0; } // clock rolled over
      if ((millis() - lastTouchTime) > TOUCH_TIME) {
        lastTouchTime = millis();
        byte arrow = whichArrow(x, y);
        if (arrow == 0) {
          return; // touch not in sweet spot
        }
        //Serial.print("which arrow = "); Serial.println(arrow);
        if (arrow > 39) { // auto/man arrows
          arrow = arrow - 40; // reduce to single digit, 0 to 7
          lowerMoistureLevel[arrow] -= 5; // decrement upper limit by 5
          if (lowerMoistureLevel[arrow] < 5) { lowerMoistureLevel[arrow] = 5;} // can't lower below five
          setArrowColor(arrow); // checks for level inversion and paints errors red
          //Serial.print("lower Moisture Level"); Serial.print(arrow); Serial.print("\t"); Serial.println(lowerMoistureLevel[arrow]);
          writeMoistureLevel(3, arrow); // update arrow
        }
        else if (arrow > 29) { // must be a valve
          arrow = arrow - 30; // reduce to single digit
          lowerMoistureLevel[arrow] += 5; // increment upper limit by 5
          if (lowerMoistureLevel[arrow] > 95) { lowerMoistureLevel[arrow] = 95;} // can't raise above 95
          setArrowColor(arrow); // checks for level inversion and paints errors red
          //Serial.print("lower Moisture Level"); Serial.print(arrow); Serial.print("\t"); Serial.println(lowerMoistureLevel[arrow]);
          writeMoistureLevel(2, arrow); // update arrow
        }
        else if (arrow > 19) { // must be a valve
          arrow = arrow - 20; // reduce to single digit
          upperMoistureLevel[arrow] -= 5; // decrement lower limit by 5
          if (upperMoistureLevel[arrow] < 10) { upperMoistureLevel[arrow] = 10;} // can't lower below ten
          setArrowColor(arrow); // checks for level inversion and paints errors red
          //Serial.print("upper Moisture Level"); Serial.print(arrow); Serial.print("\t"); Serial.println(upperMoistureLevel[arrow]);
          writeMoistureLevel(1, arrow); // update arrow
        }
        else { // must be a valve
          arrow = arrow - 10; // reduce to single digit
          upperMoistureLevel[arrow] += 5; // increment lower limit by 5
          if (upperMoistureLevel[arrow] > 100) { upperMoistureLevel[arrow] = 100;} // can't raise above 100
          setArrowColor(arrow); // checks for level inversion and paints errors red
          //Serial.print("upper Moisture Level"); Serial.print(arrow); Serial.print("\t"); Serial.println(upperMoistureLevel[arrow]);
          writeMoistureLevel(0, arrow); // update arrow
        }
      }
    }
  }
  if (oldLEDTime > millis()) {oldLEDTime = 0;} // clock rolled over
  if (millis() - oldLEDTime > MAX_LED_TIME * 60000) { // time to turn off backlight
    digitalWrite(LED_PIN, true); // turn off LED backlight
  }
  if (oldDotTime > millis()) {oldDotTime = 0;} // clock rolled over
  if (millis() - oldDotTime > DOT_TIME * 1000) { // time to print a dot
    dotCounter++;
    if(dotCounter == 80) { Serial.println(); dotCounter = 0;}
    Serial.print(".");
    oldDotTime = millis();
  }
}

void Screen0SetUp() {
  char result[8];
  uint16_t color;

  flowRate = flowMeasurement(); // this provides the initial data for subsequent comparisons
  readMoistureTemp();  // reads all sensors
  DrawBox(0, 20, 320, 240, TFT_BLUE); // clear working area
  ILI9341SetCursor(170, 32);
  DrawString("Flow Rate (ml/sec) ->", SmallFont, TFT_WHITE);
  DrawFrame(270, 22, 26, 16, TFT_WHITE); // box to contain flow rate
  ILI9341SetCursor(268, 32);
  DrawString(dtostrf(flowRate, 6, 1, result), SmallFont, TFT_WHITE); // initial value when entering screen
  ILI9341SetCursor(5, 160 + 15);
  DrawString("man", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 200 + 15);
  DrawString("auto", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 40);
  DrawString("100%", SmallFont, TFT_GREEN);
  ILI9341SetCursor(25, 40);
  DrawString("/", SmallFont, TFT_WHITE);
  ILI9341SetCursor(30, 40);
  DrawString("40C", SmallFont, TFT_RED);
  ILI9341SetCursor(10, 140);
  DrawString("0%", SmallFont, TFT_GREEN);
  ILI9341SetCursor(25, 140);
  DrawString("/", SmallFont, TFT_WHITE);
  ILI9341SetCursor(30, 140);
  DrawString("0C", SmallFont, TFT_RED);
  ILI9341SetCursor(15, 90);
  DrawString("M", SmallFont, TFT_GREEN);
  ILI9341SetCursor(25, 90);
  DrawString("/", SmallFont, TFT_WHITE);
  ILI9341SetCursor(30, 90);
  DrawString("T", SmallFont, TFT_RED);
  for (int i = 0; i < NUM_VALVES; i++) {
    // deal with temps first (red) then moisture
    for (int i = 0; i < NUM_VALVES; i++) {
      DrawBox(36 * i + 32 + 17, MENUHEIGHT * 2, 4, 100, TFT_WHITE); // set the background
      DrawBox(36 * i + 32 + 17, MENUHEIGHT * 2 + int((40 - temp[i]) * 100 / 40), 4, 100 - int((40 - temp[i]) * 100 / 40), TFT_RED); // create a red bar to indicate temperature
      DrawBox(36 * i + 32 + 15, MENUHEIGHT * 2 + int(100 - moistureLevel[i]), 8, 2, TFT_GREEN); // create a green horizontal bar to indicate moisture level - bar height 100 pixels!
    }
    color = valveState(i) ? TFT_GREEN : TFT_RED;
    DrawButton(36 * i + 19 + 17, MENUHEIGHT * 2 + 120, 30, 30, color); // upper left and box size
    color = autoManState[i] ? TFT_GREEN : TFT_RED;
    DrawButton(36 * i + 19 + 17, MENUHEIGHT * 2 + 160, 30, 30, color);
  }
}

void updateScreen0() {
  char result[8];
  uint16_t color;
  bool updateFlag = false; // Flag used to check if any item was updated.  If so, runs updateAllOld()

  if (oldFlowRate != flowRate) { // update flow if necessary
    DrawBox(271, 25, 24, 10, TFT_BLUE);
    ILI9341SetCursor(268, 32);
    DrawString(dtostrf(flowRate, 6, 1, result), SmallFont, TFT_WHITE);
  }

  for (int i = 0; i < NUM_VALVES; i++) { // update temps and moisture
    // deal with temps first (red) then moisture
    for (int i = 0; i < NUM_VALVES; i++) { // update guages
      if ((temp[i] != oldTemp[i]) || (moistureLevel[i] != oldMoistureLevel[i])) { // if either temp or moisture changes, rewrite entire bar
        DrawBox(36 * i + 32 + 15, MENUHEIGHT * 2, 8, 104, TFT_BLUE); // create a blue horizontal bar to clear gauge
        DrawBox(36 * i + 32 + 17, MENUHEIGHT * 2, 4, 100, TFT_WHITE); // set the background
        DrawBox(36 * i + 32 + 17, MENUHEIGHT * 2 + int((40 - temp[i]) * 100 / 40), 4, 100 - int((40 - temp[i]) * 100 / 40), TFT_RED); // create a red bar to indicate temperature
        DrawBox(36 * i + 32 + 15, MENUHEIGHT * 2 + int(100 - moistureLevel[i]), 8, 2, TFT_GREEN); // create a green horizontal bar to indicate moisture level
        updateFlag = true;
      }
    }
    // update manual and auto buttons
    if (valveState(i) != oldValveState[i]) {
      writeValveButton(i, valveState(i)); // update buttons
      updateFlag = true;
    }
    if (autoManState[i] != oldAutoManState[i]) {
      writeAutoManButton(i, autoManState[i]);
      updateFlag = true;
    }
  }
  if (updateFlag) {updateAllOld();}
}

void Screen1SetUp() {
  uint16_t x0, x1, x2, y0, y1, y2;
  uint16_t color;

  DrawBox(0, 20, 320, 240, TFT_BLUE); // clear working area

  ILI9341SetCursor(50, 50);
  DrawString("System Status", MediumFont, TFT_WHITE);

  systemSafe = !lowFlow && !unresponsiveSensor && !leakDetected;
  oldSystemSafe = systemSafe;
  if (systemSafe) {
    ILI9341SetCursor(80, 70);
    DrawString("System OK", SmallFont, TFT_GREEN);
  }
  else { // check each of the below and indicate alarms appropriately
    if (lowFlow) {
      ILI9341SetCursor(80, 60);
      DrawString("Low Flow", SmallFont, TFT_RED);
    }
    if (unresponsiveSensor) {
      ILI9341SetCursor(80, 70);
      DrawString("Open Sensor", SmallFont, TFT_RED);
    }
    if (leakDetected) {
      ILI9341SetCursor(80, 80);
      DrawString("Leak Detected", SmallFont, TFT_RED);
    }
  }
  DrawHLine(0, 120, 319, TFT_WHITE);
  ILI9341SetCursor(50, 110);
  DrawString("Sensor Status", MediumFont, TFT_WHITE);

  ILI9341SetCursor(5, 140);
  DrawString("temp", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 150);
  DrawString("status", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 140 + 36);
  DrawString("Msense", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 150 + 36);
  DrawString("open", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 140 + 72);
  DrawString("Msense", SmallFont, TFT_WHITE);
  ILI9341SetCursor(5, 150 + 72);
  DrawString("short", SmallFont, TFT_WHITE);

  for (uint16_t j = 0; j < 3; j++) { // draw triangles
    for (uint16_t i = 0; i < NUM_VALVES; i++) {
      x0 = 36 + 36 * i;
      x1 = x0 + 26;
      x2 = 36 + 13 + 36 * i;
      y0 = 150 + 36 * j;
      y1 = y0;
      y2 = y0 - 20;

      if (j == 0) { // these are temp sensors
        color = tempState[i] ? TFT_GREEN : TFT_RED;
      }
      else if ( j == 1) { // open moisture sensors
        color = moistureOpenState[i] ? TFT_RED : TFT_GREEN;
      }
      else { // shorted moisture sensors
        color = moistureShortState[i] ? TFT_RED : TFT_GREEN;
      }
      DrawAlarmSymbol( x2, y2, x0, y0, x1, y1, color); // x2, y2 is the peak point of the triangle
    }
  }
}

void updateScreen1() {
  uint16_t x0, x1, x2, y0, y1, y2;
  uint16_t color;
  bool updateFlag = false;

  systemSafe = !lowFlow && !unresponsiveSensor && !leakDetected;
  if ((systemSafe != oldSystemSafe) && systemSafe) {
    DrawBox(80, 52, 100, 40, TFT_BLUE); // clear top area
    ILI9341SetCursor(80, 70);
    DrawString("System OK", SmallFont, TFT_GREEN);
    oldSystemSafe = systemSafe;
  }
  else if ((systemSafe != oldSystemSafe) && !systemSafe){
    DrawBox(80, 52, 100, 40, TFT_BLUE); // clear top area for new alarm
    oldSystemSafe = systemSafe;
  }
  
  if ((lowFlow != oldLowFlow) && lowFlow) {
    ILI9341SetCursor(80, 60);
    DrawString("Low Flow", SmallFont, TFT_RED);
  }
  else if ((lowFlow != oldLowFlow) && !lowFlow) {
    DrawBox(80, 52, 100, 10, TFT_BLUE); // clear area
  }
  if ((unresponsiveSensor != oldUnresponsiveSensor) && unresponsiveSensor) {
    ILI9341SetCursor(80, 70);
    DrawString("Open Sensor", SmallFont, TFT_RED);
  }
  else if ((unresponsiveSensor != oldUnresponsiveSensor) && unresponsiveSensor) {
    DrawBox(80, 62, 100, 10, TFT_BLUE); // clear area
  }
  if ((leakDetected != oldLeakDetected) && leakDetected) {
    ILI9341SetCursor(80, 80);
    DrawString("Leak Detected", SmallFont, TFT_RED);
  }
  else if ((leakDetected != oldLeakDetected) && !leakDetected) {
    DrawBox(80, 72, 100, 10, TFT_BLUE); // clear area
  }

  for (int j = 0; j < 3; j++) { // draw triangles
    for (int i = 0; i < NUM_VALVES; i++) {
      x0 = 36 + 36 * i;
      x1 = x0 + 26;
      x2 = 36 + 13 + 36 * i;
      y0 = 150 + 36 * j;
      y1 = y0;
      y2 = y0 - 20;

      if (j == 0) { // these are the failed temp sensors
        if (tempState[i] != oldTempState[i]) {
          color = tempState[i] ? TFT_GREEN : TFT_RED;
          DrawAlarmSymbol( x2, y2, x0, y0, x1, y1, color);
          updateFlag = true;
        }
      }
      else if ( j == 1) { // open moisture sensors
        if (moistureOpenState[i] != oldMoistureOpenState[i]) {
          color = moistureOpenState[i] ? TFT_RED : TFT_GREEN;
          DrawAlarmSymbol( x2, y2, x0, y0, x1, y1, color);
          updateFlag = true;
        }
      }
      else { // shorted moisture sensors
        if (moistureShortState[i] != oldMoistureShortState[i]) {
          color = moistureShortState[i] ? TFT_RED : TFT_GREEN;
          DrawAlarmSymbol( x2, y2, x0, y0, x1, y1, color);
          updateFlag = true;
        }
      }
    }
  }
  if (updateFlag) {updateAllOld();} // makes sure that oldMoistureState[] etc. are reset
}

void Screen2SetUp() {
  uint16_t x0, x1, x2, y0, y1, y2;
  char result[16];

  DrawBox(0, 20, 320, 240, TFT_BLUE); // clear working area
  ILI9341SetCursor(2, MENUHEIGHT + 60);
  DrawString("UPPER", SmallFont, TFT_WHITE);
  ILI9341SetCursor(2, MENUHEIGHT + 60 + 100);
  DrawString("LOWER", SmallFont, TFT_WHITE);

  for (int j = 0; j < 2; j++) {
    for (int i = 0; i < NUM_VALVES; i++) {
      DrawFrame(36 * i + 36, MENUHEIGHT + 50 + j * 100, 26, 16, TFT_WHITE); // set the background
      ILI9341SetCursor(36 * i + 36 + 8, MENUHEIGHT + 60 + j * 100);
      if (j == 0) {
        DrawString(itoa(upperMoistureLevel[i], result, 10), SmallFont, TFT_WHITE);
      }
      else {
        DrawString(itoa(lowerMoistureLevel[i], result, 10), SmallFont, TFT_WHITE);
      }
    }
  }
  for (uint16_t i = 0; i < NUM_VALVES; i++) { // draw triangles
    x0 = 36 + 36 * i;
    x1 = x0 + 26;
    x2 = 36 + 13 + 36 * i;
    y0 = 65;
    y1 = y0;
    y2 = y0 - 20;
    DrawTriangle( x2, y2, x0, y0, x1, y1, TFT_GREEN);
  }
  for (uint16_t i = 0; i < NUM_VALVES; i++) { // draw triangles
    x0 = 36 + 36 * i;
    x1 = x0 + 26;
    x2 = 36 + 13 + 36 * i;
    y0 = 90;
    y1 = y0;
    y2 = y0 + 20;
    DrawTriangle(x1, y1, x0, y0, x2, y2, TFT_GREEN);
  }
  for (uint16_t i = 0; i < NUM_VALVES; i++) { // draw triangles
    x0 = 36 + 36 * i;
    x1 = x0 + 26;
    x2 = 36 + 13 + 36 * i;
    y0 = 165;
    y1 = y0;
    y2 = y0 - 20;
    DrawTriangle(x2, y2, x0, y0, x1, y1, TFT_GREEN);
  }
  for (uint16_t i = 0; i < NUM_VALVES; i++) { // draw triangles
    x0 = 36 + 36 * i;
    x1 = x0 + 26;
    x2 = 36 + 13 + 36 * i;
    y0 = 190;
    y1 = y0;
    y2 = y0 + 20;
    DrawTriangle(x1, y1, x0, y0, x2, y2, TFT_GREEN);
  }
}

#ifdef MY_MYSENSORS  
// MySensors Specific Functions
void receive(const MyMessage &message) {
  byte driverPinIndex;
  
  if (message.isAck()) {
     // if (SERIAL_TEST) {Serial.println("This is an ack from gateway");}
  }
  if (message.type == V_STATUS) { // possible sensors are:
                                  //  Digital IO -> 10 to 17
                                  //  AutoMan Switches -> 20 - 27
                                  //  SafeFlow Switch -> 44
    if (message.sensor < CHILD_ID_START_OF_VALVES + 8 && message.sensor >= CHILD_ID_START_OF_VALVES) { // must be a driver
      // Change driver state
      // Calculate driver from sensor number
      driverPinIndex = message.sensor - CHILD_ID_START_OF_VALVES; // driverPinIndex[0] thru driverPinIndex[7]
      if (!autoManState[driverPinIndex] && safeFlow) { // only change driver state if in manual mode and safeFlow
        writePORTA(driverPinIndex, message.getBool()); // turns off all valves and sets state of valve(driverPinIndex) true or false
        if(!message.getBool()) getLastFlowRate(); // make sure we get a flow measurement after valves are turned off
        for (int i = 0; i < NUM_VALVES; i++) { // set all valveStates except valveState(driverPinIndx) to false.
            if(i != driverPinIndex) {send(msgPORTA[i].set(false));}
        }
      }
      else if(!safeFlow) {
        for (int i = 0; i < NUM_VALVES; i++) { // turn off all valves
          writePORTA(i, false); // turn off all valves
          send(msgPORTA[i].set(false)); // don't know why this is necessary
        }
        getLastFlowRate(); // make sure we get a flow measurement after valves are turned off
        updateScreen0();
      }
    }
    else if (message.sensor < CHILD_ID_START_OF_AUTOS + 8 && message.sensor >= CHILD_ID_START_OF_AUTOS){ // must be an AutoMan Switch
      autoManState[message.sensor - CHILD_ID_START_OF_AUTOS] = message.getBool(); // this means state was changed by HASS
      if(!message.getBool() && valveState(message.sensor - CHILD_ID_START_OF_AUTOS)) {PORTA = 0;} // if the autoState is turning off, must also turn off associated valve if on
      updateScreen0();
    }
    else if (message.sensor == CHILD_ID_SAFEFLOW_SWITCH) { // HA requesting SafeFlow reset
      if(message.getBool() == true) {
        safeFlow = true; // user can only turn switch on.  here it's turned off again after one second.
        lowFlow = false;
        send(msgOpenSensor.set(lowFlow)); // let HA know the system is shutting down due to an open sensor 
        unresponsiveSensor = false;
        send(msgLowFlow.set(unresponsiveSensor)); // send alarm to HA to indicate system shut down.
        send(msgRestart.set(false)); // turn off the HA switch
        delay(1000);
        oldValveOnTime = millis(); 
      }    
    }
  }
  if (message.type == V_TRIPPED) { // recieved dayNight state from HA
    if (message.sensor == CHILD_ID_DAY_NIGHT) { // this is the day night switch that HA sends to prevent daytime watering
        dayNight = message.getBool(); // if true, it's daytime, do not water
    }
  }
}
#endif

// Update All
void updateAllOld(){ // update changed states

#ifdef MY_MYSENSORS  
  Serial.println("made it to MySensors UpdateAllOld");
  for (int i = 0; i < NUM_VALVES; i++) {
    if (oldValveState[i] == !valveState(i)) {send(msgPORTA[i].set(valveState(i))); oldValveState[i] = valveState(i);}
    if (oldMoistureLevel[i] != moistureLevel[i]) {send(msgAI[i].set(moistureLevel[i],1)); oldMoistureLevel[i] = moistureLevel[i];}
    if (oldTemp[i] != temp[i]) {send(msgTemp[i].set(temp[i],1)); oldTemp[i] = temp[i];}
    if (oldAutoManState[i] != autoManState[i]) {send(msgAutoMan[i].set(autoManState[i])); oldAutoManState[i] = autoManState[i];}
    Serial.print("oldTempState[");Serial.print(i);Serial.print("] = ");Serial.print(oldTempState[i]);Serial.print("   TempState[");Serial.print(i);Serial.print("] = ");Serial.println(tempState[i]);
    if (oldTempState[i] != tempState[i]) {send(msgTempState[i].set(tempState[i])); oldTempState[i] = tempState[i];}
    Serial.print("oldMoistureOpenState[");Serial.print(i);Serial.print("] = ");Serial.print(oldMoistureOpenState[i]);Serial.print("   moistureOpenState[");Serial.print(i);Serial.print("] = ");Serial.println(moistureOpenState[i]);
    if (oldMoistureOpenState[i] != moistureOpenState[i]) {
      send(msgMoistureOpenState[i].set(moistureOpenState[i])); oldMoistureOpenState[i] = moistureOpenState[i];
    }
    Serial.print("oldMoistureShortState[");Serial.print(i);Serial.print("] = ");Serial.print(oldMoistureShortState[i]);Serial.print("   moistureShortState[");Serial.print(i);Serial.print("] = ");Serial.println(moistureShortState[i]);
    if (oldMoistureShortState[i] != moistureShortState[i]) {
      send(msgMoistureShortState[i].set(moistureShortState[i])); oldMoistureShortState[i] = moistureShortState[i];
    }
  }
  if (oldFlowRate != flowRate) {send(msgFlow.set(flowRate,2)); oldFlowRate = flowRate;}
  if (oldLowFlow != lowFlow) {send(msgLowFlow.set(lowFlow)); oldLowFlow = lowFlow;} // used to let HA know that we have no water flow
  if (oldUnresponsiveSensor != unresponsiveSensor) {send(msgOpenSensor.set(unresponsiveSensor)); oldUnresponsiveSensor = unresponsiveSensor;}// used to let HA know that we may have an open sensor
#else
  for (int i = 0; i < NUM_VALVES; i++) {
    if (oldValveState[i] == !valveState(i)) { oldValveState[i] = valveState(i);}
    if (oldMoistureLevel[i] != moistureLevel[i]) {oldMoistureLevel[i] = moistureLevel[i];}
    if (oldTemp[i] != temp[i]) {oldTemp[i] = temp[i];}
    if (oldAutoManState[i] != autoManState[i]) { oldAutoManState[i] = autoManState[i];}
    if (oldTempState[i] != tempState[i]) { oldTempState[i] = tempState[i];}
    if (oldMoistureOpenState[i] != moistureOpenState[i]) {
      oldMoistureOpenState[i] = moistureOpenState[i];
    }
    if (oldMoistureShortState[i] != moistureShortState[i]) {
      oldMoistureShortState[i] = moistureShortState[i];
    }
  }
  if (oldFlowRate != flowRate) { oldFlowRate = flowRate;}
  if (oldLowFlow != lowFlow) { oldLowFlow = lowFlow;} // used to let HA know that we have no water flow
  if (oldUnresponsiveSensor != unresponsiveSensor) { oldUnresponsiveSensor = unresponsiveSensor;}// used to let HA know that we may have an open sensor
#endif
  Serial.print("*");
  for (int i = 0; i < NUM_VALVES; i++) {
    Serial.println();Serial.print("moisture level(");Serial.print(i);Serial.print(") = ");Serial.print(moistureLevel[i]);
    Serial.println();Serial.print("temperature(");Serial.print(i);Serial.print(") = ");Serial.print(temp[i]);
  }
  Serial.println();
}

// General Functions
void UpdateValvesGauges() {
  uint16_t color;

  for (int i = 0; i < NUM_VALVES; i++) {
    // deal with temps first (red) then moisture
    for (int i = 0; i < NUM_VALVES; i++) {
      DrawBox(36 * i + 32 + 17, MENUHEIGHT * 2, 4, 100, TFT_WHITE); // set the background
      DrawBox(36 * i + 32 + 17, MENUHEIGHT * 2 + (40 - temp[i]) * 100 / 40, 4, 100 - (40 - temp[i]) * 100 / 40, TFT_RED); // create a red bar to indicate temperature
      DrawBox(36 * i + 32 + 15, MENUHEIGHT * 2 + (1 - moistureLevel[i]) * 100, 8, 2, TFT_GREEN); // create a green horizontal bar to indicate moisture level
    }
    color = valveState(i) ? TFT_GREEN : TFT_RED;
    DrawButton(36 * i + 19 + 17, MENUHEIGHT * 2 + 120, 30, 30, color); // upper left and box size
    color = autoManState[i] ? TFT_GREEN : TFT_RED;
    DrawButton(36 * i + 19 + 17, MENUHEIGHT * 2 + 160, 30, 30, color);
  }
}

byte whichButton(int x, int y) {
  if (x < 36 || x > 318 || y < 160 || (int((x - 36) / 36) >  NUM_VALVES)) { // x out of button range
    return (0);
  }
  else if (y < 195) { // first row of buttons - valves
    return (10 + int((x - 36) / 36)); // returns a number between 11 and 18 to indicate row 1, collumn 0-7
  }
  else { // second row of buttons
    return (20 + int((x - 36) / 36)); // returns a number between 21 and 28 to indicate row 1, collumn 0-7
  }
}

byte whichArrow(int x, int y) {
  if (x < 36 || x > 318 || y < 40 || (int((x - 36) / 36) >  NUM_VALVES)) { // x out of button range
    return (0);
  }
  else if (y < 80) { // first row of arrows
    return (10 + int((x - 36) / 36)); // returns a number between 11 and 18 to indicate row 1, collumn 0-7
  }
  else if (y < 130) { // second row of arrows
    return (20 + int((x - 36) / 36)); // returns a number between 21 and 28 to indicate row 1, collumn 0-7
  }
  else if (y < 180) { // third row of arrows
    return (30 + int((x - 36) / 36)); // returns a number between 31 and 38 to indicate row 1, collumn 0-7
  }
  else { // fourth row of arrows
    return (40 + int((x - 36) / 36)); // returns a number between 41 and 48 to indicate row 1, collumn 0-7
  }
}

void setArrowColor(byte arrow) {
  uint16_t x0, x1, x2, y0, y1, y2;
  byte row;
  byte column;

  row = int(arrow / 10);
  column = (arrow - row * 10); // need to know what column we are changing

  if (lowerMoistureLevel[column] >= upperMoistureLevel[column]) {
    color = TFT_RED;
  }
  else {
    color = TFT_GREEN;
  }
  x0 = 36 + 36 * column;
  x1 = x0 + 26;
  x2 = 36 + 13 + 36 * column;
  y0 = 65;
  y1 = y0;
  y2 = y0 - 20;
  DrawTriangle( x2, y2, x0, y0, x1, y1, color);

  x0 = 36 + 36 * column;
  x1 = x0 + 26;
  x2 = 36 + 13 + 36 * column;
  y0 = 190;
  y1 = y0;
  y2 = y0 + 20;
  DrawTriangle(x1, y1, x0, y0, x2, y2, color);
}

void writePORTA(uint8_t pin, bool state) { // set particular pin true or false (only one bit true at a time!!!
  uint8_t newState;

  if (state) { // if the valve should be turned on
    newState = bitValue[pin]; // turns all valves off except the desired one
    PORTA = newState;
  }
  else { // if the valve should be turned off
    if (valveState(pin)) {
      PORTA = 0; // if the request valve's state is true, it must be the only on valve, therefore we can turn all valves off
    }
    // otherwise, we don't want to turn unassociated valves off
  }
}

void writeAutoManButton(uint8_t button, bool state) {
  uint16_t color;

  color = state ? TFT_GREEN : TFT_RED;
  DrawButton(36 * button + 19 + 17, MENUHEIGHT * 2 + 160, 30, 30, color);
}

void writeValveButton(uint8_t button, bool state) {
  uint16_t color;

  color = state ? TFT_GREEN : TFT_RED;
  DrawButton(36 * button + 19 + 17, MENUHEIGHT * 2 + 120, 30, 30, color); // upper left and box size
}

void writeTempState(uint8_t sensor) {
  uint16_t x0, x1, x2, y0, y1, y2;
  uint16_t color;

  x0 = 36 + 36 * sensor;
  x1 = x0 + 26;
  x2 = 36 + 13 + 36 * sensor;
  y0 = 150;
  y1 = y0;
  y2 = y0 - 20;

  color = tempState[sensor] ? TFT_GREEN : TFT_RED;
  DrawTriangle( x2, y2, x0, y0, x1, y1, color);
}

void writeOpenSensor(uint8_t sensor) {
  uint16_t x0, x1, x2, y0, y1, y2;
  uint16_t color;

  x0 = 36 + 36 * sensor; //Serial.println(x0);
  x1 = x0 + 26; //Serial.println(x1);
  x2 = 36 + 13 + 36 * sensor; //Serial.println(x2);
  y0 = 150 + 36; //Serial.println(y0);
  y1 = y0; //Serial.println(y1);
  y2 = y0 - 20; //Serial.println(y2); Serial.println();

  color = moistureOpenState[sensor] ? TFT_GREEN : TFT_RED;
  DrawTriangle( x2, y2, x0, y0, x1, y1, color);
}

void writeShortedSensor(uint8_t sensor) {
  uint16_t x0, x1, x2, y0, y1, y2;
  uint16_t color;

  x0 = 36 + 36 * sensor; //Serial.println(x0);
  x1 = x0 + 26; //Serial.println(x1);
  x2 = 36 + 13 + 36 * sensor; //Serial.println(x2);
  y0 = 150 + 72; //Serial.println(y0);
  y1 = y0; //Serial.println(y1);
  y2 = y0 - 20; //Serial.println(y2); Serial.println();

  color = moistureShortState[sensor] * TFT_GREEN + !moistureShortState[sensor] * TFT_RED;
  DrawTriangle( x2, y2, x0, y0, x1, y1, color);
}

void writeMoistureLevel(byte row, byte column) { // row is 0 or 1, column is 0 thru 7
  char result[16];

  if (row < 2) {
    row = 0;
  } else {
    row = 1;
  }
  DrawBox(36 * column + 36, MENUHEIGHT + 50 + row * 100, 26, 16, TFT_BLUE); // delete contents
  DrawFrame(36 * column + 36, MENUHEIGHT + 50 + row * 100, 26, 16, TFT_WHITE); // set the background
  ILI9341SetCursor(36 * column + 36 + 8, MENUHEIGHT + 60 + row * 100);
  if (row == 0) {
    DrawString(itoa(upperMoistureLevel[column], result, 10), SmallFont, TFT_WHITE);
  }
  else {
    DrawString(itoa(lowerMoistureLevel[column], result, 10), SmallFont, TFT_WHITE);
  }
}

// non-display related functions

bool isAnyValveOn() { 
  bool result = true;

  if (PORTA == 0 ) {result = false;}
  return(result);
}

bool isAnyAutoValveOn() {

  if (PORTA == 0 ) {
    return (false); // no valves are on, so we're ok
  }
  else { // some valve is on, is it also in auto mode?
    for (int i = 0; i < NUM_VALVES; i++) {
      if (valveState(i) && autoManState[i]) {
        return (true);
      }
    }
    return (false); // if we made it here, no valve that might be in auto state is on now
  }
}

bool valveState(uint8_t whichBit) {
  return (bitRead(PORTA, whichBit));
}

byte whichValveIsOn() {
  for (byte i = 0; i < NUM_VALVES; i++) {
    if (valveState(i)) {
      return (i);
    }
  }
}

void readMoistureTemp() {
  // get temperature data then read soil resistance and calculate moisture level
  Serial.println("made it to readMoistureTemp()");
  // read all sensors by indexing through the eight analog switches in the multiplexer (74HC4051)
  for (int index = 0; index < NUM_VALVES; index++) {
    digitalWrite(TMPS0, bitRead(tempSensorConfig[index], 0)); // write the address to the multiplexer
    digitalWrite(TMPS1, bitRead(tempSensorConfig[index], 1)); // tempSensorConfig modifies the index for the mapping
    digitalWrite(TMPS2, bitRead(tempSensorConfig[index], 2)); // of an ordered sensor configuration - see map defined above
    // call sensors.requestTemperatures() to issue a global temperature
    // as configured, there will only be one device on the bus at a time!!!
    sensors.requestTemperatures();
    // query conversion time and sleep until conversion completed
    int16_t conversionTime = sensors.millisToWaitForConversion(sensors.getResolution());
    // sleep()/wait()call can be replaced by wait() call if node need to process incoming messages (or if node is repeater)
    delay(conversionTime);
  // get temps individually
    // We use the function ByIndex to get the temperature from the first and only sensor.
    temp[index] = sensors.getTempCByIndex(0); // read the currently selected temperature sensor
    Serial.print("temp(");Serial.print(index);Serial.print(") = ");Serial.println(temp[index]);
    updateTemp(index);  
    Serial.println();
  }
  // read all the moisture levels
  digitalWrite(POWER_PIN, false); // Turn on sensor power; powers all sensors; active low
  delay(10); //delay 10 milliseconds to allow reading to settle - determined by testing
  for (int i = 0; i < NUM_VALVES; i++) { // read all moisture sensors
    uint16_t reading = analogRead(AI_pin[i]);
    Serial.print("moistureAnalogReading[");Serial.print(i);Serial.print("] = ");Serial.println(reading);
    if (reading > 900) {
      moistureOpenState[i] = true;  // are sensors open?
    } else {
      moistureOpenState[i] = false;
    }
    if (reading < 23) {
      moistureShortState[i] = true;  // are sensors shorted
    } else {
      moistureShortState[i] = false;
    }
    float x = Rseries / (1023.0001 / reading - 1.0); // 1023 is largest AI value.  0.0001 prevents overflow.
    // A = -0.0112*T +2.52
    // B = -3.6x10^-3 * T - 3.6
    float a = -0.0112 * temp[i] + 2.52;
    a = pow(10, a);
    float b = 1 / (-.0036 * temp[i] - 3.6);
    //Serial.print("Soil Resistance = "); Serial.println(x);
    moistureLevel[i] = pow(x / a, b) * 100; // was pow(x/151.35,-.27)*100
    if (moistureLevel[i] > 100) {moistureLevel[i] = 100;} // the curve fit equations do not work beyond about 80% moisture
    //Serial.print("moisture level("); Serial.print(i); Serial.print(") = "); Serial.println(moistureLevel[i]);
    //Serial.print("Analog reading = "); Serial.println(analogRead(AI_pin[i]));
    //Serial.print("Moisture Open = "); Serial.print(moistureOpenState[i]); Serial.print("    Old Moisture Open = "); Serial.println(oldMoistureOpenState[i]);
    //Serial.print("Moisture Short = "); Serial.print(moistureShortState[i]); Serial.print("    Old Moisture Short = "); Serial.println(oldMoistureShortState[i]);
  }
  digitalWrite(POWER_PIN, true); // turn off power to moisture sensors
  // Fetch temperatures from Dallas sensors
}

void updateTemp(int i) { // this simplifies the code for reading the sensors.  
  if (temp[i] == DEVICE_DISCONNECTED_C || temp[i] == -127) {// either condition indicates no sensor connected
    temp[i] = 22; // set temperature to std temp so measurements can continue
    tempState[i] = false; // keep track of failing sensors
  }
  else {
    tempState[i] = true; // keep track of working sensors
  }
  Serial.print("temp");Serial.print(i);Serial.print(" = "); Serial.println(temp[i]);
  Serial.print("tempState");Serial.print(i);Serial.print(" = "); Serial.println(tempState[i]);    
}

float flowMeasurement() { // take a second to check flow rate
  // this is a crude method used here because there are no interrupt pins left
  // in this implementation.  At the max reported flow rate through 1/4" drip
  // tubing 0f 20 GPH, we can anticipate at pulse frequency of 30 Hz.  That's
  // slow enough to make this routine work well.

  bool state = digitalRead(FLOW_PIN);
  bool oldState = state;
  bool notDone = true;
  unsigned long int count = 0;
  unsigned long int oldMillis = millis();

  while (notDone) {
    state = digitalRead(FLOW_PIN);
    if (state != oldState) {
      oldState = state;
      count++;
    }
    if ( oldMillis > millis()) {
      oldMillis = 0; // rollover event
    }
    notDone = (millis() - oldMillis < 1000); // 1000 = 1 sec: when this is false, we are done
  }
  flowRate = count / (2 * K); // gets two counts per square wave; but rising and falling!
  return (flowRate); // K is the pulses per liter (1380), so we are returning the flow rate in liters per second
  // Should be 0.022 liters per second or there abouts.
}

void getLastFlowRate() {
  delay(2000); // delay to let valve close and flow rate to settle
  flowRate = flowMeasurement(); // this takes one second to execute
}

void safeFlowShutdown() {
  safeFlow = false; // system shuts down until attended to.  When repaired, turn system off and on again.
  leakCheckFlag == true; // get ready for next leak test - this could be done on restart
  PORTA = 0; // turn all valves off (valves are active high!)
  getLastFlowRate(); // make sure flow has shut down.
  digitalWrite(SHUTOFF_VALVE, false); // turn off shutoff valve
  Serial.println();Serial.println("Shut off valve turned off in safeFlowShutdown");
}

void DrawButton(uint16_t x1, uint16_t y1, uint16_t s1, uint16_t s2, uint16_t color) {

  DrawBox(x1, y1, s1, s2, TFT_BLACK);
  DrawBox(x1 + 4, y1 + 4, s1 - 8, s2 - 8, color);
  DrawFrame(x1 + 8, y1 + 8, s1 - 16, s2 - 16, TFT_BLACK);
}

void DrawAlarmSymbol(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color) {

  DrawTriangle( x1, y1, x2, y2, x3, y3, TFT_BLACK); // x1, y1 is the peak point of the triangle
  DrawTriangle( x1, y1 + 4, x2 + 4, y2 - 2, x3 - 4, y3 - 2, color);
}

Dallas_Sensor_Address_Display_Routine.ino

C/C++
This program is used to get the addresses of the Dallas temperature sensors you will use in this project and to test their operation. The code is a modification of one of the examples provided on Github for the DallasTemperature.h library.
/* This code was obtain on Github from the examples for Miles Burtons DallasTemperature.h library and then
 *  modified slightly by me to simply obtain the device address for one sensor and print its data.  
 *  The OneWire code has been derived from http://www.arduino.cc/playground/Learning/OneWire. 
 *  
 *  Origin Credits go to:
 *  Miles Burton miles@mnetcs.com originally developed this library. 
 *  Tim Newsome nuisance@casualhacker.net added support for multiple sensors on the same bus. 
 *  Guil Barros [gfbarros@bappos.com] added getTempByAddress (v3.5) 
 *  Note: these are implemented as getTempC(address) and getTempF(address) 
 *  Rob Tillaart [rob.tillaart@gmail.com] added async modus (v3.7.0)
 */

// Include the libraries we need
#include <OneWire.h>
#include <DallasTemperature.h>

// Data wire is plugged into port 13 on the Irrigation System Board
#define ONE_WIRE_BUS 13
#define TEMPERATURE_PRECISION 9

// Setup a oneWire instance to communicate with any OneWire devices (not just Maxim/Dallas temperature ICs)
OneWire oneWire(ONE_WIRE_BUS);

// Pass our oneWire reference to Dallas Temperature.
DallasTemperature sensors(&oneWire);

// an array is required to hold each device address
DeviceAddress DallasTempSensor;

void setup(void)
{
  // start serial port
  Serial.begin(115200);
  Serial.println("Dallas Temperature Address Display Routine");

  // Start up the library
  sensors.begin();

  // locate devices on the bus
  Serial.print("Locating devices...");
  Serial.print("Found ");
  Serial.print(sensors.getDeviceCount(), DEC);
  Serial.println(" devices.");

  // report parasite power requirements
  Serial.print("Parasite power is: ");
  if (sensors.isParasitePowerMode()) Serial.println("ON");
  else Serial.println("OFF");

  // Search for devices on the bus and assign based on an index. Ideally,
  // you would do this to initially discover addresses on the bus and then
  // use those addresses and manually assign them (see MEGA Irrigation System) once you know
  // the devices on your bus (and assuming they don't change).
  //
  // method 1: by index
  if (!sensors.getAddress(DallasTempSensor, 0)) Serial.println("Unable to find address for Device 0");

  // method 2: search()
  // search() looks for the next device. Returns 1 if a new address has been
  // returned. A zero might mean that the bus is shorted, there are no devices,
  // or you have already retrieved all of them. It might be a good idea to
  // check the CRC to make sure you didn't get garbage. The order is
  // deterministic. You will always get the same devices in the same order
  //
  // Must be called before search()
  //oneWire.reset_search();
  // assigns the first address found to DallasTempSensor
  //if (!oneWire.search(DallasTempSensor)) Serial.println("Unable to find address for DallasTempSensor");

  // show the addresses we found on the bus
  Serial.print("Device 0 Address: ");
  printAddress(DallasTempSensor);
  Serial.println();

  // set the resolution to 9 bit per device
  sensors.setResolution(DallasTempSensor, TEMPERATURE_PRECISION);

  Serial.print("Device 0 Resolution: ");
  Serial.print(sensors.getResolution(DallasTempSensor), DEC);
  Serial.println();
}

// function to print a device address
void printAddress(DeviceAddress deviceAddress)
{
  for (uint8_t i = 0; i < 8; i++)
  {
    // zero pad the address if necessary
    if (deviceAddress[i] < 16) Serial.print("0");
    Serial.print(deviceAddress[i], HEX);
  }
}

// function to print the temperature for a device
void printTemperature(DeviceAddress deviceAddress)
{
  float tempC = sensors.getTempC(deviceAddress);
  if(tempC == DEVICE_DISCONNECTED_C) 
  {
    Serial.println("Error: Could not read temperature data");
    return;
  }
  Serial.print("Temp C: ");
  Serial.print(tempC);
  Serial.print(" Temp F: ");
  Serial.print(DallasTemperature::toFahrenheit(tempC));
}

// function to print a device's resolution
void printResolution(DeviceAddress deviceAddress)
{
  Serial.print("Resolution: ");
  Serial.print(sensors.getResolution(deviceAddress));
  Serial.println();
}

// main function to print information about a device
void printData(DeviceAddress deviceAddress)
{
  Serial.print("Device Address: ");
  printAddress(deviceAddress);
  Serial.print(" ");
  printTemperature(deviceAddress);
  Serial.println();
}

/*
   Main function, calls the temperatures in a loop.
*/
void loop(void)
{
  // call sensors.requestTemperatures() to issue a global temperature
  // request to all devices on the bus
  Serial.print("Requesting temperatures...");
  sensors.requestTemperatures();
  Serial.println("DONE");

  // print the device information
  printData(DallasTempSensor);
  delay(10000); // delay ten seconds
}

Credits

zavracky
1 project • 2 followers
Contact

Comments

Please log in or sign up to comment.