2018年7月14日土曜日

サーボで超簡単倒立振子

#include "Arduino.h"
#include <Wire.h>
#include <EEPROM.h>
#define IRINT_PIN 2 // IR Receive
#define LED_R 22
#define LED_G 23
#define LED_B 24
#define HCODE 0x4D //M
#define SERVO_PIN_R 10
#define SERVO_PIN_L 9
#define TONE_PIN A3
#define INT_IR 0 // IR RECEIVE interrupt number
#define IR_ON LOW
#define IR_OFF HIGH
#define IR_BUF_LEN 200
#define MIN_IR_INTERVAL 220
#define IR_CIRL 0
#define IR_UP 1
#define IR_CIRR 2
#define IR_LEFT 3
#define IR_CENTER 4
#define IR_RIGHT 5
#define IR_BAL_LF 6
#define IR_DOWN 7
#define IR_BAL_RF 8
#define IR_BAL_LB 9
#define IR_BAL_RB 10
#define MAX_IR_BUTTON 11
void sendSerial();
void resetPara();
void resetVar();
void getGyro();
void readGyro();
void calibGyro();
void calibAcc();
void calcTarget();
boolean pendDrive();
void motor();
void resetMotor();
boolean laid();
boolean upright();
boolean standing();
void getIR();
void regIR();
void printIrData();
void decodeNECAEHA();
void decodeSONY();
void irInt();
void irCommand();
void printIrData(String s);
void blinkLED(int n);
void pendulum();
void drvMotor(int pwmR, int pwmL);
void freeMotor();
void setColor(int r, int g, int b);
void readEEPROMbal();
void writeEEPROMbal();
void readEEPROMbutton();
void writeEEPROMbutton();
void selectMode();
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
int counter=0;
unsigned long time0=0;
double power, powerR, powerL;
double snsGyroZ, snsAccX;
double varAng, varOmg, varSpd, varDst, varIang, varIdst;
double gyroOffsetY, gyroOffsetZ, accOffsetX;
double gyroDataY, gyroDataZ, accDataX, accDataZ;
double gyroLSB=1.0/131.0; // deg/sec
double accLSB=1.0/16384.0; // g
double pendClk = 0.01; // in sec,
unsigned long pendInterval = 10000; // in usec
double cutoff = 0.1; // 2 * PI * f (f=Hz) //0.1
double Kang, Komg, Kdst, Kspd, Kspin, KIang, KIdst;
double spinPower;
double moveTarget, moveRate=0.0; //moveRate 0:stop, +:forward, -:backward
double moveStep = 0.0013;
double spinDestination, spinTarget;
double spinStep = 0.0;
double spinAngle;
boolean spinContinuous=false;
int pendPhase=-1;
double mechFactorR, mechFactorL;
double maxSpd;
int counterOverSpd;
int maxOverSpd=30;
double aveAccX=0.0;
double aveAccZ=0.0;
boolean debug=false;
boolean serialMonitor=false;
int pulseZeroR, pulseZeroL;
volatile unsigned long irMicroOn;
volatile unsigned long irMicroOff;
volatile unsigned int irDataOn[200];
volatile unsigned int irDataOff[200];
volatile int irOnIndex=0;
volatile int irOffIndex=0;
volatile boolean irStarted=false;
volatile boolean irDecoding=false;
volatile unsigned long lastIrTime=0;
boolean irReady=false;
byte irData[30];
unsigned int ircode;
unsigned int customerCode;
unsigned int irCustomer;
unsigned int irButton[MAX_IR_BUTTON];
int irButtonNum=-1;
int demoMode=0;
int8_t drvHLbalance=0;
boolean colorR, colorG, colorB;
void setup() {
analogWriteFrequency(10000);
attachInterrupt(INT_IR, irInt, CHANGE);
pinMode(IRINT_PIN, INPUT_PULLUP);
pinMode(LED_R, OUTPUT);
digitalWrite(LED_R, HIGH);
pinMode(LED_G, OUTPUT);
digitalWrite(LED_G, HIGH);
pinMode(LED_B, OUTPUT);
digitalWrite(LED_B, HIGH);
pinMode(12, OUTPUT);
digitalWrite(12, LOW);
pinMode(13, OUTPUT);
digitalWrite(13, HIGH);
pinMode(TONE_PIN, OUTPUT);
pinMode(A4, OUTPUT);
digitalWrite(A4, HIGH);
pinMode(A5, INPUT_PULLUP);
pinMode(A6, OUTPUT);
digitalWrite(A6, LOW);
Serial.begin(115200);
Wire.begin();
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission();
pinMode(SERVO_PIN_R, OUTPUT);
pinMode(SERVO_PIN_L, OUTPUT);
delay(100);
selectMode();
readEEPROMbal();
readEEPROMbutton();
resetPara();
resetVar();
calibGyro();
blinkLED(3);
}
void loop(){
time0=micros();
selectMode();
getIR();
getGyro();
pendulum();
counter += 1;
if (counter >= 100) {
counter = 0;
if (debug) digitalWrite(LED_R, LOW);
if (serialMonitor) sendSerial();
if (debug) digitalWrite(LED_R, HIGH);
}
while (micros() - time0 < pendInterval);
}
void pendulum() {
switch (pendPhase) {
case -1: //wait until upright
calcTarget();
motor();
if (upright()) pendPhase=0;
break;
case 0: //calib Acc
resetVar();
delay(1300);
if (!upright()) pendPhase=2;
else {
calibAcc();
if (upright()) pendPhase=1;
else pendPhase=2;
}
break;
case 1: //run
if (!standing()) {
pendPhase=6;
}
else {
// if (demoMode==2) demo8();
calcTarget();
boolean ok=pendDrive();
if (!ok) {
delay(1300);
pendPhase=2;
}
}
break;
case 2: //wait until upright
freeMotor();
if (upright()) pendPhase=0;
break;
case 6: //fell
if (laid()) pendPhase=8;
break;
case 8:
pendPhase=2;
break;
}
}
void calcTarget() {
if (spinContinuous) {
spinTarget += spinStep;
}
else {
if (spinTarget < spinDestination) spinTarget += spinStep;
if (spinTarget > spinDestination) spinTarget -= spinStep;
}
moveTarget += moveStep * moveRate;
}
boolean pendDrive() {
varSpd += power * pendClk;
varDst += Kdst * (varSpd * pendClk - moveTarget);
varIang += KIang * varAng * pendClk;
varIdst += KIdst * varDst * pendClk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 5000.0) counterOverSpd +=1;
else counterOverSpd=0;
if (counterOverSpd > maxOverSpd) {
resetMotor();
resetVar();
return false;
}
spinPower = (spinAngle - spinTarget) * Kspin;
powerL = power + spinPower;
powerR = power - spinPower;
motor();
return true;
}
void motor() {
int pwmR= (int) (constrain(powerR * mechFactorR, -maxSpd, maxSpd));
int pwmL= (int) (constrain(powerL * mechFactorL, -maxSpd, maxSpd));
drvMotor(pwmR, pwmL);
}
void drvMotor(int pwmR, int pwmL) {
int pulseR=constrain(pulseZeroR+pwmR, 1000, 2000);
int pulseL=constrain(pulseZeroL-pwmL, 1000, 2000);
bool doneR=false;
bool doneL=false;
unsigned long usec=micros();
digitalWrite(SERVO_PIN_R, HIGH);
digitalWrite(SERVO_PIN_L, HIGH);
while(!doneR || !doneL) {
unsigned long width=micros()-usec;
if (width>=pulseR) {
digitalWrite(SERVO_PIN_R, LOW);
doneR=true;
}
if (width>=pulseL) {
digitalWrite(SERVO_PIN_L, LOW);
doneL=true;
}
}
}
void getGyro() {
readGyro();
snsGyroZ = (gyroDataZ - gyroOffsetZ) * gyroLSB;
varOmg = (gyroDataY - gyroOffsetY) * gyroLSB; // unit:deg/sec
snsAccX = (accDataX - accOffsetX) * accLSB; //unit:g
spinAngle += snsGyroZ * pendClk;
varAng += (varOmg + (snsAccX * 57.3 - varAng) * cutoff ) * pendClk;
//angle filter accX=g*sin(ang) -> accX/g=sin(ang)=ang [rad] (if ang is small) -> ang=accX*57.3[deg]
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission();
Wire.requestFrom(0x68, 14);
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroDataZ = (double) gyroY;
gyroDataY = (double) gyroZ;
accDataX = -(double) accX;
aveAccX = aveAccX * 0.9 + accDataX * 0.1;
accDataZ = -(double) accY;
aveAccZ = aveAccZ * 0.9 + accDataZ * 0.1;
}
boolean laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
boolean upright() {
if (abs(aveAccZ) >13000.0) return true;
else return false;
}
boolean standing() {
if (abs(aveAccZ) >8000.0 && abs(varAng) < 40.0) return true;
else {
resetMotor();
resetVar();
return false;
}
}
void calibAcc() {
tone(TONE_PIN, 8);
accOffsetX=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
accOffsetX += accDataX;
delay(20);
}
accOffsetX /= 30.0;
noTone(TONE_PIN);
}
void calibGyro() {
tone(TONE_PIN, 8);
gyroOffsetZ=gyroOffsetY=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
gyroOffsetZ += gyroDataZ;
gyroOffsetY += gyroDataY;
delay(20);
}
gyroOffsetY /= 30.0;
gyroOffsetZ /= 30.0;
noTone(TONE_PIN);
}
void resetVar() {
power=0.0;
moveTarget=0.0;
spinDestination=0.0;
spinTarget=0.0;
spinAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
counterOverSpd=0;
spinContinuous=false;
moveRate=0.0;
}
void resetPara() {
Komg=3.5;
Kang=350.0;
KIang=1400.0;
Kspin=20.0;
Kspd=12.0;
Kdst=8.0;
KIdst=0.0;
mechFactorR=0.25;
mechFactorL=0.25;
maxSpd=1000.0;
pulseZeroR=1453;//less=forward
pulseZeroL=1478;//more=forward
}
void freeMotor() {
digitalWrite(SERVO_PIN_R, LOW);
digitalWrite(SERVO_PIN_L, LOW);
}
void resetMotor() {
drvMotor(0, 0);
counterOverSpd=0;
sendSerial();
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
setColor(1,0,0);
digitalWrite(LED_R, LOW);
delay(10);
digitalWrite(LED_R, HIGH);
delay(200);
}
}
void setColor(int r, int g, int b) {
colorR=r;
colorG=g;
colorB=b;
}
void sendSerial () {
Serial.print(micros()-time0);
Serial.print(" phase=");Serial.print(pendPhase);
// Serial.print(" dist=");Serial.print(distance);
Serial.print(" accX="); Serial.print(accDataX);
Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" temp = "); Serial.print(temp/340.0+36.53);
// Serial.print(" Omg="); Serial.print(varOmg);
Serial.print(" powerR="); Serial.print(powerR);
Serial.print(" powerL="); Serial.print(powerL);
Serial.print(" Dst="); Serial.print(varDst);
// Serial.print(" aveDst="); Serial.print(aveDst);
Serial.print(" Iang="); Serial.print(varIang);
Serial.print(", ");
Serial.print(micros()-time0);
Serial.println();
}
void getIR() {
if (!(irStarted && (micros()-irMicroOff>10000))) return;
irStarted=false;
irDecoding=true;
if (irDataOn[0]>7000) { //NEC
if (irOffIndex >=33) {
decodeNECAEHA();
printIrData("NEC");
}
}
else if (irDataOn[0]>2600) { //AEHA
if (irOffIndex >=41) {
decodeNECAEHA();
printIrData("AEHA");
}
}
else if (irDataOn[0]>1800) { //SONY
if (irOnIndex >=12) {
decodeSONY();
printIrData("SONY");
}
}
if (irReady) {
irReady=false;
lastIrTime=millis();
if (irButtonNum>=0 && irButtonNum<MAX_IR_BUTTON && pendPhase==-1) regIR();
else irCommand();
}
irDecoding=false;
}
void irCommand() {
if ((ircode==irButton[IR_CENTER])&&(customerCode==irCustomer)) {
if (pendPhase!=-1) {
if (abs(moveRate)>1.0 || abs(spinStep)>0.1) {
tone(TONE_PIN, 1000, 100);
}
demoMode=0;
spinContinuous=false;
spinStep=0.0;
moveRate=0.0;
spinDestination = spinTarget;
}
}
else if ((ircode==irButton[IR_RIGHT])&&(customerCode==irCustomer)) {
if (pendPhase==-1) {
for (int i=0; i<100; i++) {
drvMotor(-80, 0);
delay(8);
}
// drvMotor(0, 0);
}
else if (demoMode==0) {
tone(TONE_PIN, 2000, 100);
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination += 30.0;
}
}
else if ((ircode==irButton[IR_LEFT])&&(customerCode==irCustomer)) {
if (pendPhase==-1) {
for (int i=0; i<100; i++) {
drvMotor(0, -80);
delay(8);
}
// drvMotor(0, 0);
}
else if (demoMode==0) {
tone(TONE_PIN, 2000, 100);
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination -= 30.0;
}
}
else if ((ircode==irButton[IR_UP])&&(customerCode==irCustomer)) {
if (pendPhase!=-1 && demoMode==0) {
tone(TONE_PIN, 1000, 100);
moveRate-=20.0;
}
}
else if ((ircode==irButton[IR_DOWN])&&(customerCode==irCustomer)) {
if (pendPhase!=-1 && demoMode==0) {
tone(TONE_PIN, 1000, 100);
moveRate+=20.0;
}
}
else if ((ircode==irButton[IR_CIRL])&&(customerCode==irCustomer)) {
if (pendPhase!=-1 && demoMode==0) {
tone(TONE_PIN, 2000, 20);
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep-=0.3;
}
}
else if ((ircode==irButton[IR_CIRR])&&(customerCode==irCustomer)) {
if (pendPhase!=-1 && demoMode==0) {
tone(TONE_PIN, 2000, 20);
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep+=0.3;
}
}
else if ((ircode==irButton[IR_BAL_LF])&&(customerCode==irCustomer)) {
if (pendPhase==-1) {
pulseZeroL+=10;
tone(TONE_PIN, 4000, 10);
delay(20);
digitalWrite(LED_B, LOW);
writeEEPROMbalL();
digitalWrite(LED_B, HIGH);
}
}
else if ((ircode==irButton[IR_BAL_LB])&&(customerCode==irCustomer)) {
if (pendPhase==-1) {
pulseZeroL-=10;
tone(TONE_PIN, 4000, 10);
delay(20);
digitalWrite(LED_B, LOW);
writeEEPROMbalL();
digitalWrite(LED_B, HIGH);
}
}
else if ((ircode==irButton[IR_BAL_RF])&&(customerCode==irCustomer)) {
if (pendPhase==-1) {
pulseZeroR-=10;
tone(TONE_PIN, 4000, 10);
delay(20);
digitalWrite(LED_B, LOW);
writeEEPROMbalR();
digitalWrite(LED_B, HIGH);
}
}
else if ((ircode==irButton[IR_BAL_RB])&&(customerCode==irCustomer)) {
if (pendPhase==-1) {
pulseZeroR+=10;
tone(TONE_PIN, 4000, 10);
delay(20);
digitalWrite(LED_B, LOW);
writeEEPROMbalR();
digitalWrite(LED_B, HIGH);
}
}
else {
if (pendPhase == -1 && debug && irButtonNum==-1) {
digitalWrite(LED_G, LOW);
irButtonNum=0;
}
}
}
void regIR() {
if (irButtonNum<MAX_IR_BUTTON) {
irButton[irButtonNum]=ircode;
irCustomer=customerCode;
if (serialMonitor) {
Serial.print("set irButton[");
Serial.print(irButtonNum);
Serial.print("] = ");
Serial.println(ircode, HEX);
Serial.print("set irCustomer = ");
Serial.println(customerCode, HEX);
}
if (irButtonNum==0) {
irButtonNum++;
tone(TONE_PIN, 4000, 100);
}
else if (irButton[irButtonNum-1]!=ircode) {
irButtonNum++;
tone(TONE_PIN, 4000, 100);
}
else tone(TONE_PIN, 1000, 100);
if (irButtonNum==MAX_IR_BUTTON) {
delay(200);
writeEEPROMbutton();
digitalWrite(LED_G, HIGH);
}
}
}
void irInt() {
if (millis()-lastIrTime<MIN_IR_INTERVAL) return;
if (irDecoding) return;
if (digitalRead(IRINT_PIN) == IR_ON) {
irMicroOn=micros();
if (irStarted) {
irDataOff[irOffIndex]=irMicroOn-irMicroOff;
irOffIndex++;
if (irOffIndex>=IR_BUF_LEN) irStarted=false;
}
else {
irStarted=true;
irOnIndex=0;
irOffIndex=0;
irMicroOff=irMicroOn;
}
}
else {
irMicroOff=micros();
irDataOn[irOnIndex]=irMicroOff-irMicroOn;
irOnIndex++;
if (irOnIndex>=IR_BUF_LEN) irStarted=false;
}
}
void decodeNECAEHA() {
int len=irOffIndex/8;
int idx=1;
for (int i=0; i<len; i++) {
irData[i]=0;
for (int j=0; j<8; j++) {
irData[i]>>=1;
if (irDataOff[idx]>1000) irData[i]|=0x80;
idx++;
}
}
customerCode=irData[0]<<8|irData[1];
ircode=irData[len-2]<<8|irData[len-1];
irReady=true;
}
void decodeSONY() {
byte data=0;
for (int i=1; i<=7; i++) {
if (irDataOn[i]>900) data|=0x80;
data>>=1;
}
unsigned int addr=0;
int idx=8;
for (int i=0; i<16; i++) {
addr>>=1;
if (idx<irOnIndex && irDataOn[idx]<1800) {
if (irDataOn[idx]>900) addr|=0x8000;
idx++;
}
}
customerCode=addr;
ircode=(unsigned int)data;
irReady=true;
}
void printIrData(String s) {
if (!serialMonitor) return;
/*
for (int i=0; i<irOffIndex; i++) {
Serial.print(irDataOn[i]);Serial.print(" ");Serial.println(irDataOff[i]);
}
Serial.println("");
*/
Serial.println(s);
Serial.print("Customer=");Serial.println(customerCode, HEX);
Serial.print("Code=");Serial.println(ircode, HEX);
}
void readEEPROMbal() {
if (EEPROM.read(0)==HCODE) {
pulseZeroL=EEPROM.read(1)<<8|EEPROM.read(2);
pulseZeroR=EEPROM.read(3)<<8|EEPROM.read(4);
if (serialMonitor) {Serial.print("pulseZeroL=");Serial.print(pulseZeroL);Serial.print(" pulseZeroR=");Serial.println(pulseZeroR);}
}
else {
noInterrupts();
EEPROM.write(0, HCODE);
EEPROM.write(1, (byte)((pulseZeroL>>8)&0xFF));
EEPROM.write(2, (byte)(pulseZeroL&0xFF));
EEPROM.write(3, (byte)((pulseZeroR>>8)&0xFF));
EEPROM.write(4, (byte)(pulseZeroR&0xFF));
interrupts();
}
}
void writeEEPROMbalL() {
noInterrupts();
EEPROM.write(1, (byte)((pulseZeroL>>8)&0xFF));
EEPROM.write(2, (byte)(pulseZeroL&0xFF));
interrupts();
if (serialMonitor) {Serial.print("pulseZeroL=");Serial.println(pulseZeroL);}
}
void writeEEPROMbalR() {
noInterrupts();
EEPROM.write(3, (byte)((pulseZeroR>>8)&0xFF));
EEPROM.write(4, (byte)(pulseZeroR&0xFF));
interrupts();
if (serialMonitor) {Serial.print("pulseZeroR=");Serial.println(pulseZeroR);}
}
void readEEPROMbutton() {
if (EEPROM.read(5)==HCODE) {
irCustomer=EEPROM.read(6)<<8|EEPROM.read(7);
if (serialMonitor) {Serial.print("CUST=");Serial.println(irCustomer,HEX);}
for (int i=0; i<MAX_IR_BUTTON; i++) {
irButton[i]=EEPROM.read(8+i*2)<<8|EEPROM.read(9+i*2);
if (serialMonitor) {Serial.print(" CODE=");Serial.println(irButton[i],HEX);}
}
}
}
void writeEEPROMbutton() {
noInterrupts();
EEPROM.write(5, HCODE);
EEPROM.write(6, (byte)((irCustomer>>8)&0xFF));
EEPROM.write(7, (byte)(irCustomer&0xFF));
for (int i=0; i<MAX_IR_BUTTON; i++) {
EEPROM.write(8+i*2, (byte)((irButton[i]>>8)&0xFF));
EEPROM.write(9+i*2, (byte)(irButton[i]&0xFF));
}
interrupts();
}
void selectMode() {
if (digitalRead(A5)==LOW) {
debug=true;
serialMonitor=true;
}
else {
irButtonNum=-1;
digitalWrite(LED_G, HIGH);
debug=false;
serialMonitor=false;
}
}

2018年6月13日水曜日

振り子時計の精度改善

// Pend Clock Tuner V100SP
// (c) 2018 Kiraku Labo
// ESP8266
// IO 0, 2, 15 for serial flash
// IO 14, 12 for I2C SDA & SCL
// IO 13 for LED, 4 for sensor, 5 for servo.
// LCD AQM00802A-FLW-GBW
#include <ESP8266WiFi.h>
#include <WiFiClient.h>
#include <ESP8266mDNS.h>
#include <WiFiUdp.h>
#include <ESP8266WebServer.h>
#include <ArduinoOTA.h>
#include <TimeLib.h>
#include <Wire.h>
#include <ST7032.h> //modified for ESP8266
extern "C" {
#include "user_interface.h"
}
//Location dependent
#define TZH 9 //Japan +9H
//#define TZH 2 //EU Summer +2H
//Network dependent
#define STATIC_STA_IP true
#define WEB_PORT 80
IPAddress staIP(192,168,0,112);
IPAddress staGateway(192,168,0,1);
IPAddress apIP(192,168,4,112);
IPAddress subnet(255,255,255,0);
IPAddress timeServerIP(147,156,7,18); //pool.ntp.org
//IPAddress timeServerIP(210,173,160,87);//ntp.jst.mfeed.ad.jp
const char* ssid = "XXXXXXXX"; //SSID of the site
const char* pass = "XXXXXXXX"; //Pass code of the site
const char* apSsid= "XXXXXXXX"; //SSID of this device
const char* apPass = "XXXXXXXX"; //Pass code of this device
//Clock mechanism dependent
//#define PEND_CYCLE 130 //2600cycles/49min=130c/147sec determined by gear teeth count.
//#define PEND_DUR 147
#define PEND_CYCLE 7667 //PEND_CYCLE pendulum cycles per PEND_DUR seconds
#define PEND_DUR 7350
#define TRIG_WINDOW_SPAN 2 //Window in seconds to measure pendulum period after 0th second of every minute.
#define CATCH_UP_THRESH 5 //If difference is greater than this value, coil is driven in full power.
#define PRECISE_THRESH 2 //In Catchup mode, when the error become within this second, catchup mode ends.
#define ERROR_LIMIT -3600 //If error (in sec) becomes greater than this value, coil power is cut
#define PEND_STOP_DET 1500 //msec
#define MIN_TRIG_HIGH_INTERVAL 500 //msec
#define MIN_TRIG_LOW_INTERVAL 20 //msec
#define ADJ_INITIAL_LEVEL -3
//Tuner hardware dependent
#define COIL_ADDR 0x64
#define LED_PIN 13
#define SENS_PIN 4
#define PEND_LIFT_FACTOR 3 //ADJ_MIN derating 1/3
#define ADJ_MAX 63
#define ADJ_MIN -63
int16_t kP=400, kI=50;
//Sketch version
const String ver="v100S";
const String plat="Pend";
//Common
#define N_HISTORY 900 //=15H
#define MIN_HEAP 14000
#define NUM_GRAPH_SPAN 480 //points = 8H
#define NUM_WEB_DUMP 900
#define NTP_INTERVAL 300 //sec = 5min
#define NTP_PACKET_SIZE 48 //NTP time stamp is in the first 48 bytes
#define SEVENTY_YEARS 2208988800UL
WiFiUDP udp;
ST7032 lcd;
ESP8266WebServer server(WEB_PORT);
const String textHtml="text/html";
boolean serialMon=false;
uint32_t ntpLastSynch=0;
byte packetBuffer[NTP_PACKET_SIZE];
char strBuf[100];
int16_t errorHistory[N_HISTORY];
int16_t adjHistory[N_HISTORY];
time_t tHistory[N_HISTORY];
int32_t ckPendError=0, ckPendErrorMax=0, ckPendErrorMin=0, ckPendErrorLast=0;
time_t tNow, t0MinMax=0, tLast=0, tPend=0;
int16_t adjLevel=0, adjLevelMax=0, adjLevelMin=0;
float adjLevelAve=(float)ADJ_INITIAL_LEVEL;
int32_t numHistory=-1;
boolean ledColon=true, adjOn=true;
boolean catchupMode=false;
boolean wifiOk=false;
boolean timeSynched=false, setRef=false;
int16_t timeBuf[6];
volatile boolean refSet=false, pendStopped=true;
volatile int32_t ckPend=0, tRef0, countPend=0;
volatile boolean pendTrig=false, trigWindow=false;
volatile int16_t pendDir=0;
volatile uint32_t msecSensLast=0, msecSens=0, msecSensDur=0;
const String msg1 = "<html><head><meta charset='UTF-8'><title>Kiraku Labo</title>\
<script src='https://cdnjs.cloudflare.com/ajax/libs/Chart.js/2.7.1/Chart.bundle.min.js'></script>\
<style>html, body{width:95%;margin:0 auto;padding:30;background-color:#dddddd;text-align:center;font-size:30px;}</style>\
</head><body><h2>Kiraku Labo " + plat + " " + ver + "</h2>\
<form action='PC' style='display:inline'><input type='submit' value='Adj' style='font-size:60px'></form>\
<form action='PD' style='display:inline'><input type='submit' value='Slow' style='font-size:60px'></form>\
<form action='PZ' style='display:inline'><input type='submit' value='Zero' style='font-size:60px'></form>\
<form action='PU' style='display:inline'><input type='submit' value='Fast' style='font-size:60px'></form><br>\
<form action='KPD' style='display:inline'><input type='submit' value='KP dn' style='font-size:60px'></form>\
<form action='KPU' style='display:inline'><input type='submit' value='KP up' style='font-size:60px'></form>\
<form action='KID' style='display:inline'><input type='submit' value='KI dn' style='font-size:60px'></form>\
<form action='KIU' style='display:inline'><input type='submit' value='KI up' style='font-size:60px'></form><br>\
<form action='M0' style='display:inline'><input type='submit' value=' 0M ' style='font-size:60px'></form>\
<form action='H0' style='display:inline'><input type='submit' value=' 0H ' style='font-size:60px'></form>\
<form action='EZ' style='display:inline'><input type='submit' value='Zero Err' style='font-size:60px'></form>\
<form action='MR' style='display:inline'><input type='submit' value='Rst M/M' style='font-size:60px'></form><br>\
----------------------------------<br>\
<form action='ST' style='display:inline'><input type='submit' value='Status' style='font-size:60px'></form>\
<form action='HE' style='display:inline'><input type='submit' value='Err H.' style='font-size:60px'></form>\
<form action='HP' style='display:inline'><input type='submit' value='Pwr H.' style='font-size:60px'></form>\
<form action='GR' style='display:inline'><input type='submit' value='Graph' style='font-size:60px'></form>";
const String msg2 = "</body></html>";
void setup() {
pinMode(LED_PIN, OUTPUT);
Serial.begin(115200);
Wire.begin(14, 12); //14:SDA, 12:SCL
Wire.setClock(50000);
lcd.begin(8,2); //(c,r)
delay(1000);
lcd.setContrast(25);
lcd.display();
lcdDispText(0,0, "PCT " + ver);
delay(3000);
lcdDispText(0,0, "COIL CHK");
checkCoil();
drvCoil(ADJ_INITIAL_LEVEL);
adjLevel=ADJ_INITIAL_LEVEL;
adjLevelMin=ADJ_INITIAL_LEVEL;
adjLevelMax=ADJ_INITIAL_LEVEL;
setupWifi();
delay(1000);
setupServer();
setupOta();
attachInterrupt(SENS_PIN, sensInt, CHANGE);
}
void sensInt() {
int16_t sns=digitalRead(SENS_PIN);
if (pendDir==0 && sns==HIGH && millis()-msecSens>MIN_TRIG_HIGH_INTERVAL) {
pendDir=1;
digitalWrite(LED_PIN, HIGH);
pendTrig=true;
pendStopped=false;
msecSens=millis();
if (refSet) {
countPend++;
ckPend=(int32_t)((int64_t)countPend * (int64_t)PEND_DUR / (int64_t)PEND_CYCLE);
if (trigWindow) {
msecSensDur=msecSens-msecSensLast;
msecSensLast=msecSens;
}
}
}
else if (pendDir==1 && sns==LOW && millis()-msecSens>MIN_TRIG_LOW_INTERVAL) {
pendDir=0;
digitalWrite(LED_PIN, LOW);
msecSens=millis();
}
}
void loop() {
uint32_t msec=millis();
tNow=now();
if (millis()-msecSens>PEND_STOP_DET) pendStopped=true;
if (pendTrig) {
pendTrig=false;
if (refSet) updateError();
if (trigWindow) {
if (setRef) {
tRef0=tNow;
t0MinMax=tNow;
msecSensLast=msec;
refSet=true;
setRef=false;
}
trigWindow=false;
if (refSet) tune();
}
}
if (tNow!=tLast) { //every 1 sec
tLast=tNow;
if (second(tNow)==30 && wifiOk && tNow>=ntpLastSynch+NTP_INTERVAL) synchTime();
else {
lcdDispTime(0,0, tNow);
if (pendStopped && refSet) updateError();
if (second(tNow)==0) trigWindow=true;
else if (second(tNow)==TRIG_WINDOW_SPAN) {
if (trigWindow) {
trigWindow=false;
if (refSet) {
updateError();
tune();
}
}
}
}
}
server.handleClient();
ArduinoOTA.handle();
yield();
}
void synchTime() {
ledColon=false;
lcdDispText(0,0, "Get NTP ");
time_t ntpTime=setNTP();
if (ntpTime>0) {
tNow=ntpTime;
tLast=ntpTime;
ntpLastSynch=ntpTime;
ledColon=true;
lcdDispText(4,0, F(" OK "));
if (timeSynched==false) setRef=true;
timeSynched=true;
}
}
void tune() {
int32_t countPendBuf=countPend; //countPend could change by interrupt
numHistory++;
int16_t idx=numHistory % N_HISTORY;
lcdDispNum5(0,1,ckPendError);
if (adjOn) adjPend();
ckPendErrorLast=ckPendError;
lcdDispNum3n(5,1,adjLevel);
if (ckPendError<-32767) errorHistory[idx]=-32678;
else if (ckPendError<32767) errorHistory[idx]=(int16_t)ckPendError;
else errorHistory[idx]=32767;
if (numHistory<(N_HISTORY-1)) adjLevelAve = (adjLevelAve * (float)numHistory + (float)adjLevel ) / (float)(numHistory+1); //history is not full
else adjLevelAve += (float)(adjLevel-adjHistory[idx])/(float)N_HISTORY; //history is full
adjHistory[idx]=adjLevel;
tHistory[idx]=tNow;
sprintf(strBuf, "SYS:%02d/%02d %02d:%02d:%02d Cnt=%d Hst=%d Err=%d Adj=%d AdjAve=%d.%02d PND:msDur=%d",month(tNow), day(tNow), hour(tNow), minute(tNow), second(tNow),\
countPendBuf, numHistory, ckPendError, adjLevel, (int)adjLevelAve, abs((int)(adjLevelAve*100)%100), msecSensDur);
dbgPrintln(strBuf);
}
void updateError() {
ckPendError=ckPend-(int32_t)(tNow-tRef0);
if (abs(ckPendError)>30*24*3600) resetRef(); //more than 30 day difference (in case of NTP connection after while)
if (ckPendError>ckPendErrorMax) ckPendErrorMax=ckPendError;
if (ckPendError<ckPendErrorMin) ckPendErrorMin=ckPendError;
lcdDispNum5(0,1,ckPendError);
}
void resetRef() {
countPend=0;
ckPendError=0;
ckPendErrorLast=0;
tRef0=now();
t0MinMax=tRef0;
adjLevelMax=adjLevel;
adjLevelMin=adjLevel;
ckPendErrorMax=ckPendError;
ckPendErrorMin=ckPendError;
refSet=true;
}
void adjPend() {
if (abs(ckPendError)>CATCH_UP_THRESH) catchupMode=true;
if (catchupMode) {
if (ckPendError>PRECISE_THRESH) adjLevel=ADJ_MIN/PEND_LIFT_FACTOR;
else if (ckPendError<-PRECISE_THRESH) adjLevel=ADJ_MAX;
else {
catchupMode=false;
adjLevel=(int16_t)adjLevelAve;
}
}
else {
int16_t adjLevelDelta = (int16_t) ((ckPendError-ckPendErrorLast)*kP/100 + ckPendError*kI/100);
adjLevel = constrain(adjLevel-adjLevelDelta, ADJ_MIN/PEND_LIFT_FACTOR, ADJ_MAX);
}
if (ckPendError<ERROR_LIMIT) adjLevel=0;
drvCoil(adjLevel);
if (adjLevel>adjLevelMax) adjLevelMax=adjLevel;
if (adjLevel<adjLevelMin) adjLevelMin=adjLevel;
}
void drvCoil(int16_t pwr) {
byte polarity;
byte st;
int ipower;
if (pwr < 0) polarity = 1;
else polarity =2;
ipower=(byte) abs(pwr);
if (ipower == 0) polarity=0; //high z
ipower = constrain (ipower, 0, 0x3F);
st = read8830(COIL_ADDR);
if (st & 1) {
write8830(COIL_ADDR, 0, 0);
// Serial.print(adr);Serial.print(": ");Serial.println(st);
}
write8830(COIL_ADDR, ipower, polarity);
}
void write8830(byte adr, byte pwm, byte ctrl) {
Wire.beginTransmission(adr);
Wire.write(0);
byte drv=pwm*4+ctrl;
Wire.write(drv);
Wire.endTransmission(true);
}
int read8830(byte adr) {
Wire.beginTransmission(adr);
Wire.write(1);
Wire.endTransmission(false);
Wire.requestFrom((int)adr, (int)1, (int)1);
return Wire.read();
}
void checkCoil() {
for (int i=0; i<2; i++) {
drvCoil(30);
delay(5);
int ad=analogRead(A0);
if (ad>100 && ad<400) digitalWrite(13, HIGH);
else digitalWrite(13, LOW);
delay(150);
digitalWrite(13, LOW);
delay(150);
drvCoil(-30);
delay(5);
ad=analogRead(A0);
if (ad>300 && ad<700) digitalWrite(13, HIGH);
else digitalWrite(13, LOW);
delay(150);
digitalWrite(13, LOW);
delay(150);
}
}
void dbgPrint(String s) {
if (serialMon) Serial.print(s);
}
void dbgPrintln(String s) {
dbgPrint(s+F("\r\n"));
}
time_t setNTP() {
time_t tNtp=getNTPTime();
if (tNtp>0) {
setTime(tNtp);
sprintf(strBuf, "NTP:%02d/%02d %02d:%02d:%02d ", month(tNtp), day(tNtp), hour(tNtp), minute(tNtp), second(tNtp));
dbgPrintln(strBuf);
return tNtp;
}
else {
tNow=now();
sprintf(strBuf, "NTP FAILED:%02d:%02d:%02d ", hour(tNow), minute(tNow), second(tNow));
dbgPrintln(strBuf);
return 0;
}
}
time_t getNTPTime() {
int16_t pktSize;
sendNTPpacket(timeServerIP); // send an NTP packet to a time server
uint32_t usec=micros();
do {
delay(10);
pktSize = udp.parsePacket();
} while (pktSize==0 && (micros()-usec)<2000000);
if (pktSize) {
udp.read(packetBuffer, NTP_PACKET_SIZE);
uint32_t secsSince1900 = packetBuffer[40]<<24 | packetBuffer[41]<<16 | packetBuffer[42]<<8 | packetBuffer[43];
uint32_t epoch = secsSince1900 - SEVENTY_YEARS; //Unix time:
return epoch + (TZH * 3600); //TZH=time zone offset
}
else return 0;
}
void sendNTPpacket(IPAddress &address){
memset(packetBuffer, 0, NTP_PACKET_SIZE);// set all bytes in the buffer to 0
packetBuffer[0] = 0b11100011; // LI, Version, Mode
packetBuffer[1] = 0; // Stratum, or type of clock
packetBuffer[2] = 6; // Polling Interval
packetBuffer[3] = 0xEC; // Peer Clock Precision
packetBuffer[12] = 49; // 8 bytes of zero for Root Delay & Root Dispersion
packetBuffer[13] = 0x4E;
packetBuffer[14] = 49;
packetBuffer[15] = 52;
udp.beginPacket(address, 123); //NTP requests are to port 123
udp.write(packetBuffer, NTP_PACKET_SIZE);
udp.endPacket();
}
void lcdDispText(int16_t col, int16_t row, String s) {
lcd.setCursor(col,row);
lcd.print(s);
}
void lcdDispTime(int16_t col, int16_t row, time_t t) {
char tm[9];
sprintf(tm, "%02d", hour(t));
sprintf(&tm[2], ledColon?":":" ");
sprintf(&tm[3], "%02d", minute(t));
sprintf(&tm[5], ledColon?":":" ");
sprintf(&tm[6], "%02d", second(t));
lcd.setCursor(col,row);
lcd.print(tm);
}
void lcdDispNum5(int16_t col, int16_t row, int32_t n) {
char pNum[6];
if (n>=10000000) sprintf(pNum, "%s", ">1E7 ");
else if (n>=1000000) sprintf(pNum, "%03dE4", n/10000);
else if (n>=100000) sprintf(pNum, "%03dE3", n/1000);
else if (n>=-9999) sprintf(pNum, "%05d", n);
else if (n>=-99999) sprintf(pNum, "%2dE3", n/1000);
else if (n>=-999999) sprintf(pNum, "%2dE4", n/10000);
else if (n>=-9999999) sprintf(pNum, "%2dE5", n/100000);
else sprintf(pNum, "%s", "<-E7 ");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispNum3n(int16_t col, int16_t row, int32_t n) {
char pNum[4];
sprintf(pNum, "%3d", n);
lcd.setCursor(col,row);
lcd.print(pNum);
}
void handleRoot() {
server.send (200, textHtml, msg1+msg2);
}
void handleNotFound(){
server.send(404, F("text/plain"), F("File Not Found\n\n"));
}
void dispStatus() {
time_t t=now();
server.send (200, textHtml, msg1 +
"<h3>KP=" + String(kP) + " KI=" + String(kI) +
"<br>AdjOn=" + adjOn + " Catch up=" + catchupMode +
"<br>Time Now=" + String(month(t)) + "/" + String(day(t)) + " " + String(hour(t)) + ":" + preZero(String(minute(t))) +
":" + preZero(String(second(t))) +
"<br>Time NTP=" + String(month(ntpLastSynch)) + "/" + String(day(ntpLastSynch)) + " " + String(hour(ntpLastSynch)) +
":" + preZero(String(minute(ntpLastSynch))) + ":" + preZero(String(second(ntpLastSynch))) +
"<br>Time Ref=" + String(month(tRef0)) + "/" + String(day(tRef0)) + " " + String(hour(tRef0)) + ":" + preZero(String(minute(tRef0))) +
":" + preZero(String(second(tRef0))) +
"<br>Pend Ct=" + String(countPend) + " Hist=" + String(numHistory) +
"<br>M/M Reset " + String(month(t0MinMax)) + "/" + String(day(t0MinMax)) + " " + String(hour(t0MinMax)) +
":" + preZero(String(minute(t0MinMax))) + ":" + preZero(String(second(t0MinMax))) +
"<br>Error=" + String(ckPendError) + " [" + String(ckPendErrorMin) + ", " + String(ckPendErrorMax) + "]" +
"<br>Adj=" + String(adjLevel) + " [" + String(adjLevelMin) + ", " + String(adjLevelMax) + "]" +
"<br>Adj Average=" + String(adjLevelAve) +
"<br>Free Heap=" + String(system_get_free_heap_size()) + " bytes" +
"</h3>" + msg2);
}
void dispErrorHist() {
dispHist(1);
}
void dispAdjHist() {
dispHist(2);
}
void dispHist(byte n) {
if (numHistory<0) server.send (200, textHtml, msg1 + F("<h2>No History</h2>") + msg2);
else {
time_t t=now();
String st = (n==1?"Error History ":"Adj History ") + String(month(t)) + "/" + String(day(t)) + " " + String(hour(t)) + ":" + preZero(String(minute(t))) + "<br>";
int16_t count=0;
for (int32_t h=numHistory; h>numHistory-NUM_WEB_DUMP; h--) {
if (count%5==0) st += "-" + preZero(String(count)) + "m: ";
st += String(n==1?errorHistory[h%N_HISTORY]:adjHistory[h%N_HISTORY]) + ", ";
if (count%5==4) st += "<br>";
if (h==0 || system_get_free_heap_size()<MIN_HEAP) break;
count++;
}
String sz=(n==2?("<br>Adj Average=" + String(adjLevelAve)):"") +
"<br>Content length = " + String(st.length()) + " bytes" +
"<br>Free Heap=" + String(system_get_free_heap_size()) + " bytes";
server.send (200, textHtml, msg1 + F("<h3>") + st + sz + F("</h3>") + msg2);
}
}
void hand0Hour() {
time_t t=now();
if (minute(t)>40) ckPendError=(60-minute(t))*60-second(t); //Clock hand ahead
else ckPendError=-(minute(t)*60+second(t)); //Clock hand behind
countPend=(t-tRef0+ckPendError)*PEND_CYCLE/PEND_DUR;
server.send (200, textHtml, msg1 + F("<h2>Error set to ") + String(ckPendError) + "<br>countPend set to " + String(countPend) + F("</h2>") + msg2);
}
void hand0Min() {
time_t t=now();
if (second(t)>40) ckPendError=60-second(t); //Clock hand ahead
else ckPendError=-second(t); //Clock hand behind
countPend=(t-tRef0+ckPendError)*PEND_CYCLE/PEND_DUR;
server.send (200, textHtml, msg1 + F("<h2>Error set to ") + String(ckPendError) + "<br>countPend set to " + String(countPend) + F("</h2>") + msg2);
}
void zeroError() {
resetRef();
server.send (200, textHtml, msg1 + F("<h2>Reset Ref, Error set to 0</h2>") + msg2);
}
void dispAdj() {
lcdDispNum3n(5,1,adjLevel);
server.send (200, textHtml, msg1 + F("<h2>Adj= ") + String(adjLevel) +
" [" + String(adjLevelMin) + ", " + String(adjLevelMax) + F("]</h2>") + msg2);
}
void dispGraph() {
int32_t hStart=numHistory-NUM_GRAPH_SPAN;
if (hStart<0) hStart=0;
time_t tSt=(tHistory[hStart%N_HISTORY]/60)*60;
String outData = "[0,0,0";
String errData = "[5,-5,0";
String minLabel="[0,0,0";
for (int32_t i=hStart; i<=numHistory; i++) {
outData += "," + String(adjHistory[i%N_HISTORY]);
errData += "," + String(errorHistory[i%N_HISTORY]);
minLabel += "," + String((tHistory[i%N_HISTORY]-tSt)/60);
if (system_get_free_heap_size()<MIN_HEAP) break;
}
outData += "];";
errData += "];";
minLabel += "];";
String st="<h3>Error Trend " + String(month(tSt)) + "/" + String(day(tSt)) + " " + String(hour(tSt)) + ":" + preZero(String(minute(tSt))) +
" - " + String(month(tNow)) + "/" + String(day(tNow)) + " " + String(hour(tNow)) + ":" + preZero(String(minute(tNow))) + "</h3>";
st += "<canvas id='myChart' width='400' height='250'></canvas>";
st += "<script>Chart.defaults.global.defaultFontSize=30;";
st += "var ctx = document.getElementById('myChart').getContext('2d');";
st += "var errData=" + errData;
st += "var outData=" + outData;
st += "var minLabel=" + minLabel;
st += "var xLabel=[]; var i;";
st += "for (i=0; i<=" + String(numHistory-hStart+3) + "; i++) {xLabel.push(" + String(tSt-TZH*3600) + "000 + minLabel[i]*60000);outData[i]/=5;}";
st += "var errLine={label:'Error(sec)', showLine:true, lineTension:0, fill:false, borderWidth:5, borderColor:'blue', pointRadius:0, data:errData};";
st += "var outLine={label:'Output/5', showLine:true, lineTension:0, fill:false, borderWidth:1, borderColor:'red', pointRadius:0, data:outData};";
st += "var opt={scales: {xAxes: [{type: 'time', time: {displayFormats: {millisecond:'kk:mm',second:'kk:mm',minute:'kk:mm',hour:'M/D ha',}}}]}};";
st += "var config={type:'line', options: opt, data: {datasets: [errLine, outLine], labels: xLabel}};";
st += "var myChart = new Chart(ctx,config);</script>";
st += "<h3>Free Heap=" + String(system_get_free_heap_size()) + " bytes</h3>";
server.send(200, "text/html", msg1 + st + msg2);
}
void adjControl() {
if (adjOn) {
adjOn=false;
lcdDispText(0,1, "ADJ= ");
}
else {
adjOn=true;
lcdDispText(0,1, " ");
}
server.send (200, textHtml, msg1 + F("<h2>Control= ") + String(adjOn) + F("</h2>") + msg2);
}
void adjZero() {
adjLevel=0;
drvCoil(0);
dispAdj();
}
void adjUp(){
if (adjLevel<=ADJ_MAX-5) adjLevel +=5;
else adjLevel=ADJ_MAX;
drvCoil(adjLevel);
dispAdj();
}
void adjDwn(){
if (adjLevel>=ADJ_MIN+5) adjLevel -=5;
else adjLevel=ADJ_MIN;
drvCoil(adjLevel);
dispAdj();
}
String preZero(String s) {
if (s.length()==1) return "0"+s;
else return s;
}
void resetErrorHistory() {
for (int16_t i=0; i<N_HISTORY; i++) {
errorHistory[i]=0;
}
}
void paramIUp() {
kI += 10;
server.send (200, textHtml, msg1 + F("<h2>KI= ") + String(kI) + F("</h2>") + msg2);
}
void paramIDn() {
kI -= 10;
server.send (200, textHtml, msg1 + F("<h2>KI= ") + String(kI) + F("</h2>") + msg2);
}
void paramPUp() {
kP += 10;
server.send (200, textHtml, msg1 + F("<h2>KP= ") + String(kP) + F("</h2>") + msg2);
}
void paramPDn() {
kP -= 10;
server.send (200, textHtml, msg1 + F("<h2>KP= ") + String(kP) + F("</h2>") + msg2);
}
void resetMinMax() {
adjLevelMax=adjLevel;
adjLevelMin=adjLevel;
ckPendErrorMax=ckPendError;
ckPendErrorMin=ckPendError;
t0MinMax=now();
dispStatus();
}
void setupServer() {
server.on("/", handleRoot);
server.on("/PC", adjControl);
server.on("/PD", adjDwn);
server.on("/PZ", adjZero);
server.on("/PU", adjUp);
server.on("/KPD", paramPDn);
server.on("/KPU", paramPUp);
server.on("/KID", paramIDn);
server.on("/KIU", paramIUp);
server.on("/M0", hand0Min);
server.on("/H0", hand0Hour);
server.on("/EZ", zeroError);
server.on("/MR", resetMinMax);
server.on("/ST", dispStatus);
server.on("/HE", dispErrorHist);
server.on("/HP", dispAdjHist);
server.on("/GR", dispGraph);
server.onNotFound(handleNotFound);
server.begin();
}
void setupWifi() {
uint32_t msec;
lcdDispText(0,0, F("WIFI...."));
WiFi.mode(WIFI_AP_STA);
#if (STATIC_STA_IP)
WiFi.config(staIP, staGateway, subnet);
#endif
WiFi.begin(ssid, pass);
msec=millis();
int16_t st;
do {
st=WiFi.status();
delay(20);
} while (st!= WL_CONNECTED && millis()-msec<10000);
if (st==WL_CONNECTED) {
lcdDispText(4,0, F(" OK "));
delay(1000);
IPAddress ipadr=WiFi.localIP();
lcdDispText(0,0, " . .");
lcdDispNum3n(0,0, ipadr[0]);
lcdDispNum3n(4,0, ipadr[1]);
lcdDispText(0,1, " . ");
lcdDispNum3n(0,1, ipadr[2]);
lcdDispNum3n(4,1, ipadr[3]);
delay(3000);
wifiOk=true;
udp.begin(2390);
msec=millis();
time_t ret;
do {
ret=setNTP();
delay(10);
} while (ret==0 && millis()-msec<10000);
if (ret) {
timeSynched=true;
setRef=true;
ledColon=true;
lcdDispText(0,0, "NTP OK ");
}
else lcdDispText(0,0, F("NTP NG "));
delay(2000);
}
else {
lcdDispText(4,0, F(" NG "));
WiFi.mode(WIFI_AP);
delay(3000);
wifiOk=false;
setRef=true;
}
WiFi.softAPConfig(apIP, apIP, subnet);
WiFi.softAP(apSsid, apPass);
}
void setupOta() {
ArduinoOTA.onStart([]() {
dbgPrintln(F("Start"));
});
ArduinoOTA.onEnd([]() {
dbgPrintln(F("\nEnd"));
});
ArduinoOTA.onProgress([](uint16_t progress, uint16_t total) {
dbgPrint(F("Progress: "));dbgPrintln(String(progress / (total / 100)));
});
ArduinoOTA.onError([](ota_error_t error) {
dbgPrint(F("Error["));dbgPrint(String(error));dbgPrint(F("]: "));
if (error == OTA_AUTH_ERROR) dbgPrintln(F("Auth Failed"));
else if (error == OTA_BEGIN_ERROR) dbgPrintln(F("Begin Failed"));
else if (error == OTA_CONNECT_ERROR) dbgPrintln(F("Connect Failed"));
else if (error == OTA_RECEIVE_ERROR) dbgPrintln(F("Receive Failed"));
else if (error == OTA_END_ERROR) dbgPrintln(F("End Failed"));
});
ArduinoOTA.begin();
dbgPrint(F("IP address: "));
dbgPrintln(WiFi.localIP().toString());
}