2020年8月10日月曜日

M5StickCとJoyCでBLEリモコン

 バランスロボを操縦するためのBLEリモコンを作ってみました。

micro:bitバランスロボの記事はこちらです。

M5StickCバランスロボの記事はこちらです。


//
// JoyC Balance Robot Controller
// by Kiraku Labo
//
#include <M5StickC.h>
#include <BLEDevice.h>
#include <Ticker.h>
#define LED 10
#define JOYC_ADDR 0x38
#define JOYC_COLOR_REG 0x20
#define JL_X16 0x50
#define JL_Y16 0x52
#define JR_X16 0x54
#define JR_Y16 0x56
#define JOYC_LEFT_X_REG 0x60
#define JOYC_LEFT_Y_REG 0x61
#define JOYC_RIGHT_X_REG 0x62
#define JOYC_RIGHT_Y_REG 0x63
#define JOYC_PRESS_REG 0x64
#define JOYC_LEFT_ANGLE_REG 0x70
#define JOYC_LEFT_DISTANCE_REG 0x74 //radius?
#define JOYC_RIGHT_ANGLE_REG 0x72
#define JOYC_RIGHT_DISTANCE_REG 0x76
BLEUUID serviceUUID("75719c1e-6299-11e8-adc0-fa7ae01bbebc");
BLEUUID charaUUID_RX("7571a1e6-6299-11e8-adc0-fa7ae01bbebc");
BLEUUID charaUUID_TX("75719f7a-6299-11e8-adc0-fa7ae01bbebc");
BLERemoteCharacteristic* pRemoteCharacteristicRX;
BLERemoteCharacteristic* pRemoteCharacteristicTX;
BLEAdvertisedDevice* periphDevice;
BLEScanResults *scanCompleteCB;
Ticker timer;
boolean connecting = false;
boolean scanning = false;
bool connected = false;
char errCode='0';
String errStr="";
TFT_eSprite dispBuff = TFT_eSprite(&M5.Lcd);
TFT_eSprite voltBuff = TFT_eSprite(&M5.Lcd);
extern const unsigned char connect_on[800];
extern const unsigned char connect_off[800];
byte ledColor[3]={0,100,0};
uint8_t joyStick[5];
float vBatt, voltAve=3.7;
volatile uint16_t loopCounter=1, loopCounter0=0;
void setup() {
pinMode(LED,OUTPUT);
digitalWrite(LED,HIGH);
Serial.begin(115200);
M5.begin();
Wire.begin(0,26,10000);
M5.Lcd.setRotation(4);
M5.Lcd.setSwapBytes(false);
dispBuff.createSprite(80, 160);
dispBuff.setSwapBytes(true);
dispBuff.fillRect(0,0,80,20, dispBuff.color565(50,50,50));
dispBuff.setTextSize(1);
dispBuff.setTextColor(GREEN);
dispBuff.setCursor(55,6);
dispBuff.pushSprite(0,0);
setupBLE();
i2cWriteBuff(JOYC_COLOR_REG, ledColor, 3);
timer.attach(5.0, watch); //2 sec
}
void watch() {
if (loopCounter==loopCounter0) {
digitalWrite(LED, LOW);
esp_restart();
}
loopCounter0=loopCounter;
}
void loop() {
getJoystick();
dispLcd();
if (connecting == true) {
Serial.println("Connecting...");
if (connectBLE()) {
Serial.println("Connected to the BLE Server.");
dispBuff.fillRect(0,0,80,20, dispBuff.color565(50,50,50));
dispBuff.setCursor(5,5);
dispBuff.setTextSize(2);
dispBuff.print("*");
dispBuff.pushSprite(0,0);
}
else {
Serial.println("Failed to connect BLE server.");
dispBuff.fillRect(0,0,80,20, dispBuff.color565(50,50,50));
dispBuff.setTextSize(1);
dispBuff.setCursor(20,5);
dispBuff.printf("Failed");
dispBuff.pushSprite(0,0);
}
connecting = false;
}
if (connected) {
pRemoteCharacteristicTX->writeValue(joyStick, 5, false); //do not expect response
// Serial.printf("Sent:%d %d", joyStick[2], joyStick[3]);
}
else if (scanning) {
dispBuff.pushImage(0,0,20,20,(uint16_t *)connect_off);
dispBuff.fillRect(0,0,80,20, dispBuff.color565(50,50,50));
dispBuff.setTextSize(1);
dispBuff.setCursor(13,5);
dispBuff.printf("scanning..");
dispBuff.pushSprite(0,0);
BLEDevice::getScan()->start(1, false);
}
M5.update();
if (M5.BtnB.wasPressed()) {
dispBuff.fillRect( 0,30,80,130,BLACK);
dispBuff.setTextSize(2);
dispBuff.setCursor(10,45);
dispBuff.printf("RESET");
dispBuff.pushSprite(0,0);
delay(500);
esp_restart();
}
loopCounter=(loopCounter+1)%1000;
delay(50);
}
void getJoystick() {
for (int i = 0; i < 5; i++) {
joyStick[i] = i2cReadByte(0x60 + i);
}
}
void dispLcd() {
dispBuff.setTextSize(2);
dispBuff.fillRect( 0,30,80,130,BLACK);
dispBuff.setCursor(5,30);
dispBuff.printf("R %03d",joyStick[2]);
dispBuff.setCursor(28,47);
dispBuff.printf("%03d",joyStick[3]);
dispBuff.setCursor(5,70);
dispBuff.printf("L %03d",joyStick[0]);
dispBuff.setCursor(28,87);
dispBuff.printf("%03d",joyStick[1]);
dispBuff.setCursor(5,111);
if (errCode!='0') dispBuff.print(errStr);
else dispBuff.print(" ");
float vBatt= M5.Axp.GetBatVoltage();
dispBuff.setCursor(10,140);
dispBuff.printf("%4.2fV ", vBatt);
dispBuff.pushSprite(0,0);
}
void i2cWriteBuff(uint8_t addr, uint8_t* data, uint16_t len) {
Wire.beginTransmission(0x38);
Wire.write(addr);
for (int i = 0; i < len; i++) {
Wire.write(data[i]);
}
Wire.endTransmission();
}
uint8_t i2cReadByte(uint8_t addr) {
Wire.beginTransmission(0x38);
Wire.write(addr);
Wire.endTransmission();
Wire.requestFrom(0x38, 1);
return Wire.read();
}
class funcClientCallbacks: public BLEClientCallbacks {
void onConnect(BLEClient* pClient) {
};
void onDisconnect(BLEClient* pClient) {
Serial.println("Disconnected");
pRemoteCharacteristicRX->registerForNotify(NULL);
delete periphDevice;
connected = false;
}
};
class advertisedDeviceCallbacks: public BLEAdvertisedDeviceCallbacks {
void onResult(BLEAdvertisedDevice advertisedDevice) {
Serial.print("Advertised Device found: ");
Serial.println(advertisedDevice.getName().c_str());
if (advertisedDevice.haveServiceUUID()) {
BLEUUID service = advertisedDevice.getServiceUUID();
if (service.equals(serviceUUID)) {
BLEDevice::getScan()->stop();
dispBuff.fillRect(0,0,80,20, dispBuff.color565(50,50,50));
dispBuff.setTextSize(1);
dispBuff.setCursor(10,5);
dispBuff.printf("Connecting");
dispBuff.pushSprite(0,0);
periphDevice = new BLEAdvertisedDevice(advertisedDevice);
connecting = true;
scanning = true;
}
}
scanning =true;
}
};
static void notifyCallback(BLERemoteCharacteristic* pBLERemoteCharacteristic,
uint8_t* pData, size_t length, bool isNotify) {
errCode=pData[0];
errStr=(char*)pData;
if (errCode!='0') {
Serial.print("Error:");
Serial.println((char*)pData);
}
}
void setupBLE() {
BLEDevice::init("");
BLEScan* pBLEScan = BLEDevice::getScan();
pBLEScan->setAdvertisedDeviceCallbacks(new advertisedDeviceCallbacks());
pBLEScan->setActiveScan(true);
dispBuff.setTextSize(1);
dispBuff.setCursor(17,5);
dispBuff.printf("Scanning");
dispBuff.pushSprite(0,0);
pBLEScan->start(1, false);
}
bool connectBLE() {
Serial.print("Forming a connection to ");
Serial.println(periphDevice->getAddress().toString().c_str());
BLEClient* pClient = BLEDevice::createClient();
Serial.println(" - Created client");
pClient->setClientCallbacks(new funcClientCallbacks());
pClient->connect(periphDevice);
Serial.println(" - Connected to server");
BLERemoteService* pRemoteService = pClient->getService(serviceUUID);
if (pRemoteService == nullptr) {
Serial.print("Failed to find serviceUUID: ");
Serial.println(serviceUUID.toString().c_str());
pClient->disconnect();
return false;
}
Serial.println("Found ServiceUUID");
pRemoteCharacteristicRX = pRemoteService->getCharacteristic(charaUUID_RX);
if (pRemoteCharacteristicRX == nullptr) {
Serial.print("Failed to find characteristicUUID: ");
Serial.println(charaUUID_RX.toString().c_str());
pClient->disconnect();
return false;
}
Serial.println("Found CharaUUID RX");
if(pRemoteCharacteristicRX->canNotify()) {
pRemoteCharacteristicRX->registerForNotify(notifyCallback);
}
pRemoteCharacteristicTX = pRemoteService->getCharacteristic(charaUUID_TX);
if (pRemoteCharacteristicTX == nullptr) {
Serial.print("Failed to find charaUUID_TX: ");
Serial.println(charaUUID_TX.toString().c_str());
pClient->disconnect();
return false;
}
Serial.println("Found CharaUUID TX");
connected = true;
return true;
}
view raw JoyCBLEV09.ino hosted with ❤ by GitHub

micro:bitと電動消しゴムでバランスロボ

ハードウェアは こちらをご覧ください。

PWM周波数の変更のため、wiring_analog_nRF51.c 内の関数 void analogWrite( uint32_t ulPin, uint32_t ulValue ) の

NRF_TIMER1->PRESCALER = (NRF_TIMER1->PRESCALER & ~TIMER_PRESCALER_PRESCALER_Msk) | ((7 << TIMER_PRESCALER_PRESCALER_Pos) & TIMER_PRESCALER_PRESCALER_Msk);

を 

NRF_TIMER1->PRESCALER = (NRF_TIMER1->PRESCALER & ~TIMER_PRESCALER_PRESCALER_Msk) | ((3 << TIMER_PRESCALER_PRESCALER_Pos) & TIMER_PRESCALER_PRESCALER_Msk);

 に変更しました。

 また、i2cのタイムアウトのために、Wire_nRF51.cpp 内の関数 uint8_t TwoWire::endTransmission(bool stopBit) の

    _p_twi->TXD = txBuffer.read_char();
    while(!_p_twi->EVENTS_TXDSENT && !_p_twi->EVENTS_ERROR) ;


     _p_twi->TXD = txBuffer.read_char();
    uint32_t usecTimeOut=micros();
    while(!_p_twi->EVENTS_TXDSENT && !_p_twi->EVENTS_ERROR) {
      if (micros()-usecTimeOut>3000) return 4;
    }

 に変更しました。

以下ソースコードです。

//
// Keshgomu Robo
// by Kiraku Labo
//
// MPU: micro:bit(nRF51822)
// Motor driver: KS0308(TB6612)
// Gyro: GY-521(MPU6050)
// IR: GP1UXC41QS
//
#include <Wire.h>
#include <BLEPeripheral.h>
#define KY0308
#define BUTTON_A 5
#define BUTTON_B 11
#define BATT 0
#define IRPIN 8
#define DRV_RESET 14
#ifdef KY0308
#define PWMA 1
#define PWMB 2
#define INA1 13
#define INA2 12
#define INB1 15
#define INB2 16
#endif
#define NUM_IR_KEY 12
#define HEADER 0x4D
#define MIN_IR_INTERVAL 220
#define IR_BUF_LEN 200
#define IR_ON LOW
#define IR_OFF HIGH
BLEPeripheral blePeripheral = BLEPeripheral();
BLEService service = BLEService("75719c1e-6299-11e8-adc0-fa7ae01bbebc");
BLECharacteristic chRx = BLECharacteristic("75719f7a-6299-11e8-adc0-fa7ae01bbebc", BLEWriteWithoutResponse, 10);
BLECharacteristic chTx = BLECharacteristic("7571a1e6-6299-11e8-adc0-fa7ae01bbebc", BLENotify, 20);
extern "C" {void TIMER2_IRQHandler() {intHandler();}}
byte serialMon=1; //0:No Serial 1:Brief 2:Verbose
boolean dbg=true;
uint16_t ver=49;
int16_t state=-1;
int16_t accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
volatile int16_t loopCounter=1, loopCounter0=0;
uint32_t time0=0, time1=0;
float power, powerR, powerL;
float gyroZdps, accXg;
float varAng, varOmg, varSpd, varDst, varIang, aveAbsOmg=0.0;;
float gyroZoffset, gyroYoffset, accXoffset;
float gyroXdata, gyroZdata, gyroYdata, accXdata, accYdata, accZdata;
float gyroLSB=1.0/32.8; //at FS=1000dps, 1.0/131.0; //at FS=250dps
float accLSB=1.0/16384.0; // g
float cutoff=0.01; //~=2 * pi * f (Hz) assuming clk is negligible compared to 1/w
float clk=0.01; // in sec,
uint32_t interval=10; // in msec
float aveAccZ=0.0;
int32_t distance;
float Komg, Kang, KIang, Kyaw, Kspd, Kdst;
float mechFactorR, mechFactorL;
int16_t maxSpd;
int16_t maxOvs=30;
int16_t punchSpd, drvOffset;
float yawPower;
float movePower=0.0, movePwrTarget, movePwrStep=1.0;
float spinDest, spinTarget, spinFact=1.0;
float spinStep=0.0;
float yawAng;
bool spinContinuous=false;
int16_t motorDeadBand=0;
int16_t counterOverSpd;
int16_t ipowerR=0, ipowerL=0;
int16_t motorRdir=0, motorLdir=0; //stop 1:+ -1:-
float battFactor;
int16_t drvRsim=0, drvLsim=0;
float lrBalance=0.0, spinBalAdj=0.0;
float volt;
volatile byte ledBuf[3][9];
volatile byte ledRow=0;
volatile uint16_t irqCounter=0;
uint16_t devCode[NUM_IR_KEY+1] = {0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF, 0x10EF};
uint16_t keyCode[NUM_IR_KEY+1] = {0xFFFF, 0xB14E, 0xA05F, 0x21DE, 0x10EF, 0x20DF, 0x807F, 0x11EE, 0x00FF, 0x817E, 0xF807, 0x7887, 0x58A7};
int16_t keyId=-1;
volatile uint32_t irMicroOn, irMicroOff;
volatile uint16_t irDataOn[200], irDataOff[200];
volatile int16_t irOnIndex=0, irOffIndex=0;
volatile boolean irStarted=false, irDecoding=false;
volatile uint32_t lastIrTime=0;
boolean keyCodeReady=false;
byte irData[30];
uint16_t irKeyCode, irDevCode;
bool byIrRemote=true; //true=TV remote, false=BLE joystick
float angAdj=0.0;
byte joyLX, joyLY, joyRX, joyRY, joySW;
bool errWDT=false, errFell=false, errBat=false, errOvs=false, erri2c=false;
float errData=0.0;
const byte rowIO[3] = {26, 27, 28};
const byte colIO[9] = {3, 4, 10, 23, 24, 25, 9, 7, 6};
const byte rowIndx[5][5] = {{0,1,0,1,0}, {2,2,2,2,2}, {1,0,1,2,1}, {0,0,0,0,0}, {2,1,2,1,2}};
const byte colIndx[5][5] = {{0,3,1,4,2}, {3,4,5,6,7}, {1,8,2,8,0}, {7,6,5,4,3}, {2,6,0,5,1}};
const byte ledEmptyHeart[] = {0x0A, 0x15, 0x11, 0x0A, 0x04};
const byte ledFilledHeart[] = {0x0A, 0x1F, 0x1F, 0x0E, 0x04};
const byte ledSmile[] = {0x00, 0x0A, 0x00, 0x11, 0x0E};
const byte ledFrown[] = {0x00, 0x0A, 0x00, 0x0E, 0x11};
const byte ledFont[38][5] = {
{0x04, 0x0A, 0x0A, 0x0A, 0x04}, // 0
{0x04, 0x0C, 0x04, 0x04, 0x0E}, // 1
{0x1C, 0x02, 0x0C, 0x10, 0x1E}, // 2
{0x1E, 0x02, 0x04, 0x12, 0x0C}, // 3
{0x04, 0x0C, 0x14, 0x1E, 0x04}, // 4
{0x1C, 0x10, 0x1C, 0x02, 0x1C}, // 5
{0x0C, 0x10, 0x1C, 0x12, 0x0C}, // 6
{0x0E, 0x02, 0x02, 0x04, 0x08}, // 7
{0x0C, 0x12, 0x0C, 0x12, 0x0C}, // 8
{0x0C, 0x12, 0x0E, 0x02, 0x0C}, // 9
{0x0C, 0x12, 0x1E, 0x12, 0x12}, // A
{0x1C, 0x12, 0x1C, 0x12, 0x1C}, // B
{0x0C, 0x12, 0x10, 0x12, 0x0C}, // C
{0x1C, 0x12, 0x12, 0x12, 0x1C}, // D
{0x1E, 0x10, 0x1C, 0x10, 0x1E}, // E
{0x1E, 0x10, 0x1C, 0x10, 0x10}, // F
{0x0C, 0x10, 0x16, 0x12, 0x0C}, // G
{0x12, 0x12, 0x1E, 0x12, 0x12}, // H
{0x0E, 0x04, 0x04, 0x04, 0x0E}, // I
{0x1E, 0x04, 0x04, 0x14, 0x08}, // J
{0x12, 0x14, 0x18, 0x14, 0x12}, // K
{0x08, 0x08, 0x08, 0x08, 0x0E}, // L
{0x12, 0x1E, 0x12, 0x12, 0x12}, // M
{0x12, 0x1A, 0x16, 0x12, 0x12}, // N
{0x0C, 0x12, 0x12, 0x12, 0x0C}, // O
{0x1C, 0x12, 0x1C, 0x10, 0x10}, // P
{0x0C, 0x12, 0x12, 0x0C, 0x06}, // Q
{0x1C, 0x12, 0x1C, 0x14, 0x12}, // R
{0x0E, 0x10, 0x0C, 0x02, 0x1C}, // S
{0x0E, 0x04, 0x04, 0x04, 0x04}, // T
{0x12, 0x12, 0x12, 0x12, 0x0C}, // U
{0x12, 0x12, 0x12, 0x0A, 0x04}, // V
{0x12, 0x12, 0x12, 0x1E, 0x12}, // W
{0x12, 0x12, 0x0C, 0x12, 0x12}, // X
{0x12, 0x0A, 0x04, 0x04, 0x04}, // Y
{0x1E, 0x04, 0x08, 0x10, 0x1E}, // Z
{0x00, 0x00, 0x00, 0x00, 0x00}, // space
{0x00, 0x00, 0x00, 0x00, 0x04}}; // .
void setup() {
delay(100);
pinMode(BATT, INPUT);
pinMode(BUTTON_A, INPUT_PULLUP);
pinMode(BUTTON_B, INPUT_PULLUP);
pinMode(IRPIN, INPUT_PULLUP);
pinMode(DRV_RESET, OUTPUT);
digitalWrite(DRV_RESET, LOW);
delay(10);
digitalWrite(DRV_RESET, HIGH);
Serial.begin(115200);
attachInterrupt(IRPIN, irInt, CHANGE);
Wire.begin();
Wire.setClock(50000L);
setupMPU6050();
setupTimer();
setupBLE();
ledInit();
resetPara();
resetVar();
showVer();
setupMotorDriver(); //allow one sec for moto:bit firmware to be ready ater DRV_RESET
getBaseline1();
ledClear();
}
void loop() {
getIR();
getGyro();
checkBLE();
if (digitalRead(BUTTON_A)==LOW) showVolt();
if (digitalRead(BUTTON_B)==LOW) {
delay(500);
getBaseline1();
}
if (state==-1) {
if (abs(accXdata)<0.2 && aveAbsOmg<1.0) {
errFell=false;
errOvs=false;
digitalWrite(DRV_RESET, HIGH);
state=0;
}
else driveSim();
}
else if (state==0) {
calibrate();
drawBitmap(ledSmile);
state=1;
}
else if (state==1) {
if (abs(aveAccZ)<0.5 || counterOverSpd>maxOvs) {
if (counterOverSpd>maxOvs) {
errOvs=true;
errData=(float)maxOvs;
}
else {
errFell=true;
errData=aveAccZ;
}
resetMotor();
resetVar();
sendStatus();
state=-1;
}
else {
calcTarget();
drive();
}
}
loopCounter += 1;
char err='0';
if (loopCounter%10==0) { //every 0.1 sec
getBattVolt();
setBattFact();
if (errWDT) err='W';
else if (erri2c) err='I';
else if (errBat) err='B';
else if (errOvs) err='S';
else if (errFell) {
err='F';
drawBitmap(ledFrown);
}
else {
err='0';
drawBitmap(ledSmile);
}
if (err!='0' && err!='F') ledPrint(err);
}
if (loopCounter>=100) { //every 1 sec
loopCounter=0;
if (errFell || errOvs || errBat) sendBLE(String(err)+String(errData));
else sendBLE(String(err));
sendStatus();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void getBaseline1() {
ledClear();
drawBitmap(ledEmptyHeart);
gyroZoffset=gyroYoffset=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
gyroYoffset += gyroYdata;
gyroZoffset += gyroZdata;
delay(20);
}
gyroYoffset /= 30.0;
gyroZoffset /= 30.0;
ledClear();
}
void calibrate() {
resetVar();
resetMotor();
drawBitmap(ledFilledHeart);
delay(300);
sendStatus();
getBaseline2();
ledClear();
}
void getBaseline2() {
gyroZoffset=accXoffset=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
accXoffset += accXdata;
gyroZoffset += gyroZdata;
delay(20);
}
accXoffset /= 30.0;
gyroZoffset /= 30.0;
}
void resetVar() {
power=0.0;
movePwrTarget=0.0;
spinDest=0.0;
spinTarget=0.0;
spinStep=0.0;
yawAng=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
angAdj=0.0;
}
void sendStatus() {
if (serialMon==0) return;
char buf[30];
sprintf(buf, "[%d", millis()-time0); Serial.print(buf);
// sprintf(buf, " st=%d", state); Serial.print(buf);
// sprintf(buf, " aX=%.2f", accXdata); Serial.print(buf);
// sprintf(buf, " aY=%.2f", accY); Serial.print(buf);
// sprintf(buf, " avZ=%.2f", aveAccZ); Serial.print(buf);
// sprintf(buf, " ang=%.2f", varAng); Serial.print(buf);
sprintf(buf, " MPT=%.2f", movePwrTarget); Serial.print(buf);
sprintf(buf, " yPwr=%.2f", yawPower); Serial.print(buf);
// sprintf(buf, " pwrL=%.2f", powerL); Serial.print(buf);
// sprintf(buf, " pwrR=%.2f", powerR); Serial.print(buf);
// sprintf(buf, " drvL=%d", drvLsim); Serial.print(buf);
// sprintf(buf, " drvR=%d", drvRsim); Serial.print(buf);
// sprintf(buf, " spT=%.2f", spinTarget); Serial.print(buf);
// sprintf(buf, " Omg=%5.1f", varOmg); Serial.print(buf);
// sprintf(buf, " power=%5.0f", power); Serial.print(buf);
// sprintf(buf, " Iang=%5.0f", varIang); Serial.print(buf);
sprintf(buf, " %d]", millis()-time0); Serial.print(buf);
Serial.println();
Serial.flush();
}
void calcTarget() {
if (spinContinuous) {
if (abs(movePower)>=5.0) spinFact=constrain((powerR+powerL)/15.0, -1.0, 1.0); //moving
else spinFact=1.0; //standing
spinTarget += spinStep * spinFact;
}
else {
if (abs(spinDest-spinTarget)>=abs(spinStep)) spinTarget += spinStep;
else spinTarget=spinDest;
}
calcMoveTarget();
}
void calcMoveTarget() {
if (movePwrTarget < movePower+spinBalAdj-movePwrStep) movePwrTarget += movePwrStep;
else if (movePwrTarget > movePower+spinBalAdj+movePwrStep) movePwrTarget -= movePwrStep;
else movePwrTarget = movePower+spinBalAdj;
}
void drive() {
varAng += angAdj;
varSpd += power * clk;
varDst += Kdst * (varSpd * clk);
varIang += KIang * varAng * clk;
power = varIang + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 1000.0) counterOverSpd += 1;
else counterOverSpd =0;
if (counterOverSpd > maxOvs) return;
power=constrain(power, -maxSpd, maxSpd);
yawPower = (yawAng - spinTarget) * Kyaw;
powerR = power + yawPower + movePwrTarget;
powerL = power - yawPower + movePwrTarget;
ipowerR = (int16_t) constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd);
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorR(max(ipowerR, motorDeadBand)+drvOffset);
else drvMotorR(max(ipowerR, motorDeadBand) + punchSpd+drvOffset);
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorR(min(ipowerR, -motorDeadBand)+drvOffset);
else drvMotorR(min(ipowerR, -motorDeadBand) - punchSpd+drvOffset);
motorRdir = -1;
}
else {
drvMotorR(0);
motorRdir = 0;
}
ipowerL = (int16_t) constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd);
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorL(max(ipowerL, motorDeadBand)+drvOffset);
else drvMotorL(max(ipowerL, motorDeadBand) + punchSpd+drvOffset);
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorL(min(ipowerL, -motorDeadBand)+drvOffset);
else drvMotorL(min(ipowerL, -motorDeadBand) - punchSpd+drvOffset);
motorLdir = -1;
}
else {
drvMotorL(0);
motorLdir = 0;
}
}
void driveSim() {
spinTarget = 20.0*spinStep * spinFact;
calcMoveTarget();
yawPower = ( - spinTarget) * Kyaw;
powerR = yawPower + movePwrTarget;
powerL = -yawPower + movePwrTarget;
ipowerR = (int16_t) constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd);
if (ipowerR > 0) {
if (motorRdir == 1) drvRsim=(max(ipowerR, motorDeadBand)+drvOffset);
else drvRsim=(max(ipowerR, motorDeadBand) + punchSpd+drvOffset);
drvMotorR(drvRsim);
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvRsim=(min(ipowerR, -motorDeadBand)+drvOffset);
else drvRsim=(min(ipowerR, -motorDeadBand) - punchSpd+drvOffset);
drvMotorR(drvRsim);
motorRdir = -1;
}
else {
drvRsim=0;
drvMotorR(0);
motorRdir = 0;
}
ipowerL = (int16_t) constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd);
if (ipowerL > 0) {
if (motorLdir == 1) drvLsim=(max(ipowerL, motorDeadBand)+drvOffset);
else drvLsim=(max(ipowerL, motorDeadBand) + punchSpd+drvOffset);
drvMotorL(drvLsim);
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvLsim=(min(ipowerL, -motorDeadBand)+drvOffset);
else drvLsim=(min(ipowerL, -motorDeadBand) - punchSpd+drvOffset);
drvMotorL(drvLsim);
motorLdir = -1;
}
else {
drvLsim=0;
drvMotorL(0);
motorLdir = 0;
}
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
counterOverSpd=0;
}
#ifdef KY0308
void resetPara() {
Kang=35.0;
Komg=0.7;
KIang=700.0;
Kyaw=3.0;
Kdst=25.0;
Kspd=5.0;
mechFactorR=0.45;
mechFactorL=0.5;
punchSpd=15;
motorDeadBand=5;
drvOffset=0;
maxSpd=200;
lrBalance=0.0;
}
void setupMotorDriver() {
//IN1,IN2: 0,0=hi z, 1,0=OUT1ON/OUT2OFF, 0,1=OUT1OFF/OUT2ON, 1,1=brake
pinMode(INA2, OUTPUT);
pinMode(INA1, OUTPUT);
pinMode(INB1, OUTPUT);
pinMode(INB2, OUTPUT);
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
digitalWrite(14, HIGH);
}
void drvMotorR(int pwm) {
if (pwm>0) {
digitalWrite(15, LOW);
digitalWrite(16, HIGH);
analogWrite(2, pwm);
}
else if (pwm<0) {
digitalWrite(15, HIGH);
digitalWrite(16, LOW);
analogWrite(2, -pwm);
}
else {
digitalWrite(15, HIGH);
digitalWrite(16, HIGH);
analogWrite(2, 0);
}
}
void drvMotorL(int pwm) {
if (pwm>0) {
digitalWrite(12, LOW);
digitalWrite(13, HIGH);
analogWrite(1, pwm);
}
else if (pwm<0) {
digitalWrite(12, HIGH);
digitalWrite(13, LOW);
analogWrite(1, -pwm);
}
else {
digitalWrite(12, HIGH);
digitalWrite(13, HIGH);
analogWrite(1, 0);
}
}
#endif //KY0308
void getGyro() {
readGyro();
varOmg = (gyroYdata - gyroYoffset);
if (state!=1) aveAbsOmg = aveAbsOmg * 0.9 + abs(varOmg) * 0.1;
yawAng += (gyroZdata - gyroZoffset) * clk;
varAng += (varOmg + ((accXdata - accXoffset) * 57.3 - varAng) * cutoff ) * clk;
// varAng = (varAng+ varOmg*clk)*0.999 + accXg*57.3 *0.001;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
int16_t err=Wire.endTransmission();
if (err) {
Serial.println("i2c timeout");Serial.flush();
erri2c=true;
reseti2c();
return;
}
else erri2c=false;
Wire.requestFrom(0x68, 14, true);
accZ=(Wire.read()<<8|Wire.read()); //0x3B acc x
accY=Wire.read()<<8|Wire.read(); //0x3D acc y
accX=Wire.read()<<8|Wire.read(); //0x3F acc z
temp=Wire.read()<<8|Wire.read(); //0x41
gyroZ=-(Wire.read()<<8|Wire.read()); //0x43 gyro x
gyroY=(Wire.read()<<8|Wire.read()); //0x45 gyro y
gyroX=Wire.read()<<8|Wire.read(); //0x47 gyro z
gyroXdata = (float) gyroX * gyroLSB;
gyroZdata = (float) gyroZ * gyroLSB;
gyroYdata = (float) gyroY * gyroLSB;
accXdata = (float) accX * accLSB;
accYdata = (float) accY * accLSB;
accZdata = (float) accZ * accLSB;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
}
void setupMPU6050() {
Wire.beginTransmission(0x68);
Wire.write(0x6B); // Power management register
Wire.write((byte)0x00); // wake up
Wire.endTransmission();
Wire.beginTransmission(0x68);
Wire.write(0x1B); // Gyro config register
Wire.write((byte)0x10); // Gyro full scale 0x00=250deg/s, 0x08=500deg/s, 0x10=1000deg/s, 0x18=2000deg/s
Wire.endTransmission();
}
void reseti2c() {
Wire.end();
pinMode(20, INPUT);
for (byte i=0; i<20; i++) {
pinMode(19, INPUT);
delayMicroseconds(5);
pinMode(19, OUTPUT);
digitalWrite(19, LOW);
delayMicroseconds(5);
}
pinMode(19, INPUT);
delayMicroseconds(10);
Wire.begin();
}
void getBattVolt() {
volt=(float)analogRead(0)*9.9/1023.0;
if (volt<7.0) {
errBat=true;
errData=volt;
}
else errBat=false;
}
void setBattFact() {
if (volt>=4.0) battFactor=6.0/volt;
else battFactor=1.0;
}
void showVer() {
ledPrint('V');
delay(500);
ledPrint(ver/10);
delay(500);
ledPrint('.');
delay(500);
ledPrint(ver%10);
delay(500);
ledClear();
showVolt();
}
void showVolt() {
getBattVolt();
ledPrint('B');
delay(500);
ledPrint((byte)volt);
delay(500);
ledPrint('.');
delay(500);
ledPrint((byte)(volt*10.0)%10);
delay(800);
}
void ledClear() {
for (byte r=0; r<3; r++) {
for (byte c=0; c<9; c++) {
ledBuf[r][c]=0;
}
}
}
void ledPrint(byte c) {
if (c<=9) drawBitmap(ledFont[c]);
else if (c==' ') drawBitmap(ledFont[36]);
else if (c=='.') drawBitmap(ledFont[37]);
else if (c<='9') drawBitmap(ledFont[c-'0']);
else drawBitmap(ledFont[c-'A'+10]);
}
void ledInit() {
for (byte c=0; c<9 ; c++) {
pinMode(colIO[c], OUTPUT);
digitalWrite(colIO[c], HIGH);
}
for (byte r=0; r<3 ; r++) {
pinMode(rowIO[r], OUTPUT);
digitalWrite(rowIO[r], LOW);
}
for (byte r=0; r<3; r++) {
for (byte c=0; c<9; c++) {
ledBuf[r][c]=0;
}
}
ledRow=0;
}
void ledHandler() {
digitalWrite(rowIO[ledRow], LOW);
ledRow = ++ledRow % 3;
for (byte c=0; c<9; c++) {
if (ledBuf[ledRow][c]) digitalWrite(colIO[c], LOW);
else digitalWrite(colIO[c], HIGH);
}
digitalWrite(rowIO[ledRow], HIGH);
}
void drawBitmap(const byte* bitmap) {
ledClear();
for (byte y=0; y<5; y++) {
byte b = bitmap[y];
for (byte x=0; x<5; x++) {
if(b & 0x10) drawPixel(x, y, 1);
b <<= 1;
}
}
}
void drawPixel(byte x, byte y, byte on) { //on:0 or 1
byte col=colIndx[y][x];
byte row=rowIndx[y][x];
ledBuf[row][col]=on;
}
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 (keyCodeReady) {
keyCodeReady=false;
lastIrTime=millis();
irCommand();
}
irDecoding=false;
}
void irCommand() {
for (int i=0; i<=NUM_IR_KEY; i++) {
if (irKeyCode==keyCode[i] && irDevCode==devCode[i]) {
byIrRemote=true;
irExec(i);
break;
}
}
}
void irExec(int i) {
switch (i) {
case 1: //veer left
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep-=0.3;
break;
case 2: //forward
if (abs(movePower)>0.1 && abs(spinStep)>0.1) spinStep=0.0;
else {
movePower+=20.0;
// varAng-=1.0;
// angAdj=-movePower/2000.0;
}
break;
case 3: //veer right
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep+=0.3;
break;
case 4: //spin left
if (spinContinuous) spinDest=spinTarget;
spinContinuous=false;
spinStep=-0.3;
spinDest -= 30.0;
break;
case 5: //stop
spinContinuous=false;
varAng +=movePower/50.0;
spinStep=0.0;
movePower=0.0;
spinDest = spinTarget;
break;
case 6: //spin right
if (spinContinuous) spinDest=spinTarget;
spinContinuous=false;
spinStep=0.3;
spinDest += 30.0;
break;
case 7: //Serial monitor mode
break;
case 8: //backward
if (abs(movePower)>0.1 && abs(spinStep)>0.1) spinStep=0.0;
else {
movePower-=20.0;
// varAng +=1.0;
// angAdj=-movePower/2000.0;
}
break;
case 9:
break;
case 10:
serialMon++;
if (serialMon==3) serialMon=0;
Serial.println("Serial Monitor Mode=" + String(serialMon));
break;
}
}
void irInt() {
if (millis()-lastIrTime<MIN_IR_INTERVAL) return;
if (irDecoding) return;
if (digitalRead(IRPIN) == 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() {
int16_t len=irOffIndex/8;
int16_t 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++;
}
}
irDevCode=irData[0]<<8|irData[1];
irKeyCode=irData[len-2]<<8|irData[len-1];
keyCodeReady=true;
}
void decodeSONY() {
byte data=0;
for (int i=1; i<=7; i++) {
if (irDataOn[i]>900) data|=0x80;
data>>=1;
}
uint16_t addr=0;
int16_t idx=8;
for (int i=0; i<16; i++) {
addr>>=1;
if (idx<irOnIndex && irDataOn[idx]<1800) {
if (irDataOn[idx]>900) addr|=0x8000;
idx++;
}
}
irDevCode=addr;
irKeyCode=(uint16_t)data;
keyCodeReady=true;
}
void printIrData(String s) {
if (serialMon==0) return;
if (serialMon==2) {
for (int i=0; i<irOffIndex; i++) {
Serial.print(irDataOn[i]);Serial.print(" ");Serial.println(irDataOff[i]);
}
Serial.println("");
}
Serial.print(s);
Serial.print(" Dev=");Serial.print(irDevCode, HEX);
Serial.print(" Key=");Serial.println(irKeyCode, HEX);
}
void setupBLE() {
blePeripheral.setDeviceName("MICROBIT");
blePeripheral.setLocalName("keshigomu");
blePeripheral.setAdvertisedServiceUuid(service.uuid());
blePeripheral.addAttribute(service);
blePeripheral.addAttribute(chRx);
blePeripheral.addAttribute(chTx);
blePeripheral.begin();
}
void checkBLE() {
// blePeripheral.poll();
BLECentral central = blePeripheral.central();
if (central) {
if (central.connected()) {
if (chRx.written()) {
if (chRx.value()) {
joyLX=chRx.value()[0];
joyLY=chRx.value()[1];
joyRX=chRx.value()[2];
joyRY=chRx.value()[3];
joySW=chRx.value()[4];
bleCommand();
// Serial.print(joyRX);Serial.print(" ");Serial.println(joyRY);
}
}
}
}
}
void bleCommand() {
int8_t jX=(constrain(joyRX,0,200)-100)/20; //-5 to 5 = Right to Left
int8_t jY=(constrain(joyLY,0,200)-100)/20; //-5 to 5 = Down to Up
if (jX!=0 || jY!=0) byIrRemote=false;
if (!byIrRemote) { //joystick
spinContinuous=true;
spinStep=-0.3*(float)jX;
movePower=(float)jY*20.0;
if (jY==0) spinBalAdj=-(float)jX*lrBalance;
else spinBalAdj=0.0;
angAdj=-movePower/100000.0;
}
}
void sendBLE(String s) {
char buf[20]={}; //init with 0
byte len=s.length();
if (len>=19) len=19;
memcpy(buf, s.c_str(), len);
chTx.setValue((byte*)buf, len+1); //last byte=0
}
void setupTimer() {
NRF_TIMER2->TASKS_STOP = 1;
NRF_TIMER2->TASKS_CLEAR = 1;
NRF_TIMER2->MODE = TIMER_MODE_MODE_Timer;
NRF_TIMER2->PRESCALER = 5; // prescaler 1/32(500kHz)
NRF_TIMER2->BITMODE = TIMER_BITMODE_BITMODE_16Bit;
NRF_TIMER2->CC[0] = 500; // comparator (1msec, 1kHz)
NRF_TIMER2->INTENSET = (TIMER_INTENSET_COMPARE0_Enabled << TIMER_INTENSET_COMPARE0_Pos);
NRF_TIMER2->SHORTS = (TIMER_SHORTS_COMPARE0_CLEAR_Enabled << TIMER_SHORTS_COMPARE0_CLEAR_Pos);
NVIC_SetPriority(TIMER2_IRQn, 3);
NVIC_ClearPendingIRQ(TIMER2_IRQn);
NVIC_EnableIRQ(TIMER2_IRQn);
NRF_TIMER2->TASKS_START=1;
}
void intHandler() {
NRF_TIMER2->EVENTS_COMPARE[0]=0;
ledHandler();
irqCounter = ++irqCounter%50;
if (irqCounter==0) { //every 50msec
if (state==1) { //watch dog
if (loopCounter==loopCounter0) {
digitalWrite(DRV_RESET, LOW);
errWDT=true;
reseti2c();
}
else loopCounter0=loopCounter;
}
}
}
view raw KS03K49.ino hosted with ❤ by GitHub

2020年6月10日水曜日

BalaC Balancing Robot - One-wheel Drive Versiion

The software is basically the same as the previous one.  Just changed parameters to drive only one wheel.

//
// BalaC balancing robot (IMU:MPU6886)
// by Kiraku Labo
//
// 1. Lay the robot flat, and power on.
// 2. Wait until Gal-1 (Pitch Gyro calibration) completes.
// 3. Hold still the robot upright in balance until Cal-2 (Accel & Yaw Gyro cal) completes.
//
// short push of power button: Gyro calibration
//
#include <M5StickC.h>
#define LED 10
#define N_CAL1 100
#define N_CAL2 100
#define LCDV_MID 60
boolean serialMonitor=true;
boolean standing=false;
int16_t counter=0;
uint32_t time0=0, time1=0;
int16_t counterOverPwr=0, maxOvp=20;
float power, powerR, powerL, yawPower;
float varAng, varOmg, varSpd, varDst, varIang;
float gyroXoffset, gyroYoffset, gyroZoffset, accXoffset;
float gyroXdata, gyroYdata, gyroZdata, accXdata, accZdata;
float aveAccX=0.0, aveAccZ=0.0, aveAbsOmg=0.0;
float cutoff=0.1; //~=2 * pi * f (Hz)
const float clk = 0.01; // in sec,
const uint32_t interval = (uint32_t) (clk*1000); // in msec
float Kang, Komg, KIang, Kyaw, Kdst, Kspd;
int16_t maxPwr;
float yawAngle=0.0;
float moveDestination, moveTarget;
float moveRate=0.0;
const float moveStep=0.2*clk;
int16_t fbBalance=0;
int16_t motorDeadband=0;
float mechFactR, mechFactL;
int8_t motorRDir=0, motorLDir=0;
bool spinContinuous=false;
float spinDest, spinTarget, spinFact=1.0;
float spinStep=0.0; //deg per 10msec
int16_t ipowerL=0, ipowerR=0;
int16_t motorLdir=0, motorRdir=0; //0:stop 1:+ -1:-
float vBatt, voltAve=3.7;
int16_t punchPwr, punchPwr2, punchDur, punchCountL=0, punchCountR=0;
byte demoMode=0;
void setup() {
pinMode(LED, OUTPUT);
digitalWrite(LED, HIGH);
Serial.begin(115200);
M5.begin();
Wire.begin(0, 26); //SDA,SCL
imuInit();
M5.Axp.ScreenBreath(11);
M5.Lcd.setRotation(2);
M5.Lcd.setTextFont(4);
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setTextSize(1);
resetMotor();
resetPara();
punchPwr2=max(punchPwr, motorDeadband);
resetVar();
calib1();
#ifdef DEBUG
debugSetup();
#else
setMode(false);
#endif
}
void loop() {
checkButtonP();
#ifdef DEBUG
if (debugLoop1()) return;
#endif
getGyro();
if (!standing) {
dispBatVolt();
aveAbsOmg = aveAbsOmg * 0.9 + abs(varOmg) * 0.1;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
M5.Lcd.setCursor(10,130);
M5.Lcd.printf("%5.2f ", -aveAccZ);
if (abs(aveAccZ)>0.9 && aveAbsOmg<1.5) {
calib2();
if (demoMode==1) startDemo();
M5.Axp.ScreenBreath(7);
standing=true;
}
}
else {
if (abs(varAng)>30.0 || counterOverPwr>maxOvp) {
resetMotor();
resetVar();
standing=false;
setMode(false);
M5.Axp.ScreenBreath(11);
}
else {
drive();
}
}
counter += 1;
if (counter >= 100) {
counter = 0;
dispBatVolt();
if (serialMonitor) sendStatus();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void calib1() {
calDelay(30);
digitalWrite(LED, LOW);
calDelay(80);
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setCursor(0, LCDV_MID);
M5.Lcd.print(" Cal-1 ");
gyroYoffset=0.0;
for (int i=0; i <N_CAL1; i++){
readGyro();
gyroYoffset += gyroYdata;
delay(9);
}
gyroYoffset /= (float)N_CAL1;
M5.Lcd.fillScreen(BLACK);
digitalWrite(LED, HIGH);
}
void calib2() {
resetVar();
resetMotor();
digitalWrite(LED, LOW);
calDelay(80);
M5.Lcd.setCursor(0, LCDV_MID);
M5.Lcd.println(" Cal-2 ");
accXoffset=0.0;
gyroZoffset=0.0;
for (int i=0; i <N_CAL2; i++){
readGyro();
accXoffset += accXdata;
gyroZoffset += gyroZdata;
delay(9);
}
accXoffset /= (float)N_CAL2;
gyroZoffset /= (float)N_CAL2;
M5.Lcd.fillScreen(BLACK);
digitalWrite(LED, HIGH);
}
void checkButtonP() {
byte pbtn=M5.Axp.GetBtnPress();
if (pbtn==2) calib1(); //short push
else if (pbtn==1) setMode(true); //long push
}
void calDelay(int n) {
for (int i=0; i<n; i++) {
getGyro();
delay(9);
}
}
void setMode(bool inc) {
if (inc) demoMode=++demoMode%2;
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setCursor(5, 5);
if (demoMode==0) M5.Lcd.print("Stand ");
else if (demoMode==1) M5.Lcd.print("Demo ");
}
void startDemo() {
moveRate=1.0;
spinContinuous=true;
spinStep=-40.0*clk;
}
void resetPara() {
Kang=35.0;
Komg=0.8;
KIang=700.0;
Kyaw=0.0;
Kdst=60.0;
Kspd=3.0;
mechFactL=0.7;
mechFactR=0.0;
punchPwr=25;
punchDur=1;
fbBalance=0;
motorDeadband=14;
maxPwr=127;
}
void getGyro() {
readGyro();
varOmg = (gyroYdata-gyroYoffset); //unit:deg/sec
yawAngle += (gyroZdata-gyroZoffset) * clk; //unit:g
varAng += (varOmg + ((accXdata-accXoffset) * 57.3 - varAng) * cutoff ) * clk; //complementary filter
}
void readGyro() {
float gX, gY, gZ, aX, aY, aZ;
M5.Imu.getGyroData(&gX,&gY,&gZ);
M5.Imu.getAccelData(&aX,&aY,&aZ);
gyroYdata=gX;
gyroZdata=-gY;
gyroXdata=-gZ;
accXdata=aZ;
accZdata=aY;
}
void drive() {
#ifdef DEBUG
debugDrive();
#endif
if (abs(moveRate)>0.1) spinFact=constrain(-(powerR+powerL)/10.0, -1.0, 1.0); //moving
else spinFact=1.0; //standing
if (spinContinuous) spinTarget += spinStep * spinFact;
else {
if (spinTarget < spinDest) spinTarget += spinStep;
if (spinTarget > spinDest) spinTarget -= spinStep;
}
moveTarget += moveStep * (moveRate +(float)fbBalance/100.0);
varSpd += power * clk;
varDst += Kdst * (varSpd * clk -moveTarget);
varIang += KIang * varAng * clk;
power = varIang + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 1000.0) counterOverPwr += 1;
else counterOverPwr =0;
if (counterOverPwr > maxOvp) return;
power = constrain(power, -maxPwr, maxPwr);
yawPower = (yawAngle - spinTarget) * Kyaw;
powerR = power - yawPower;
powerL = power + yawPower;
ipowerL = (int16_t) constrain(powerL * mechFactL, -maxPwr, maxPwr);
int16_t mdbn=-motorDeadband;
int16_t pp2n=-punchPwr2;
if (ipowerL > 0) {
if (motorLdir == 1) punchCountL = constrain(++punchCountL, 0, 100);
else punchCountL=0;
motorLdir = 1;
if (punchCountL<punchDur) drvMotorL(max(ipowerL, punchPwr2));
else drvMotorL(max(ipowerL, motorDeadband));
}
else if (ipowerL < 0) {
if (motorLdir == -1) punchCountL = constrain(++punchCountL, 0, 100);
else punchCountL=0;
motorLdir = -1;
if (punchCountL<punchDur) drvMotorL(min(ipowerL, pp2n));
else drvMotorL(min(ipowerL, mdbn));
}
else {
drvMotorL(0);
motorLdir = 0;
}
ipowerR = (int16_t) constrain(powerR * mechFactR, -maxPwr, maxPwr);
if (ipowerR > 0) {
if (motorRdir == 1) punchCountR = constrain(++punchCountR, 0, 100);
else punchCountR=0;
motorRdir = 1;
if (punchCountR<punchDur) drvMotorR(max(ipowerR, punchPwr2));
else drvMotorR(max(ipowerR, motorDeadband));
}
else if (ipowerR < 0) {
if (motorRdir == -1) punchCountR = constrain(++punchCountR, 0, 100);
else punchCountR=0;
motorRdir = -1;
if (punchCountR<punchDur) drvMotorR(min(ipowerR, pp2n));
else drvMotorR(min(ipowerR, mdbn));
}
else {
drvMotorR(0);
motorRdir = 0;
}
}
void drvMotorL(int16_t pwm) {
drvMotor(0, (int8_t)constrain(pwm, -127, 127));
}
void drvMotorR(int16_t pwm) {
drvMotor(1, (int8_t)constrain(-pwm, -127, 127));
}
void drvMotor(byte ch, int8_t sp) {
Wire.beginTransmission(0x38);
Wire.write(ch);
Wire.write(sp);
Wire.endTransmission();
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
counterOverPwr=0;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
moveRate=0.0;
spinContinuous=false;
spinDest=0.0;
spinTarget=0.0;
spinStep=0.0;
yawAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
}
void sendStatus () {
Serial.print(millis()-time0);
Serial.print(" stand="); Serial.print(standing);
Serial.print(" accX="); Serial.print(accXdata);
Serial.print(" power="); Serial.print(power);
Serial.print(" ang=");Serial.print(varAng);
Serial.print(", ");
Serial.print(millis()-time0);
Serial.println();
}
void imuInit() {
M5.Imu.Init();
if (M5.Imu.imuType=M5.Imu.IMU_MPU6886) {
M5.Mpu6886.SetGyroFsr(M5.Mpu6886.GFS_250DPS); //250DPS 500DPS 1000DPS 2000DPS
M5.Mpu6886.SetAccelFsr(M5.Mpu6886.AFS_4G); //2G 4G 8G 16G
if (serialMonitor) Serial.println("MPU6886 found");
}
else if (serialMonitor) Serial.println("MPU6886 not found");
}
void dispBatVolt() {
M5.Lcd.setCursor(5, LCDV_MID);
vBatt= M5.Axp.GetBatVoltage();
M5.Lcd.printf("%4.2fv ", vBatt);
}
//
// BalaC balancing robot (IMU:MPU6886)
// by Kiraku Labo
//
// 1. Lay the robot flat, and power on.
// 2. Wait until Gal-1 (Pitch Gyro calibration) completes.
// 3. Hold still the robot upright in balance until Cal-2 (Accel & Yaw Gyro cal) completes.
//
// short push of power button: Gyro calibration
//
#include <M5StickC.h>
#define LED 10
#define N_CAL1 100
#define N_CAL2 100
#define LCDV_MID 60
boolean serialMonitor=true;
boolean standing=false;
int16_t counter=0;
uint32_t time0=0, time1=0;
int16_t counterOverPwr=0, maxOvp=20;
float power, powerR, powerL, yawPower;
float varAng, varOmg, varSpd, varDst, varIang;
float gyroXoffset, gyroYoffset, gyroZoffset, accXoffset;
float gyroXdata, gyroYdata, gyroZdata, accXdata, accZdata;
float aveAccX=0.0, aveAccZ=0.0, aveAbsOmg=0.0;
float cutoff=0.1; //~=2 * pi * f (Hz)
const float clk = 0.01; // in sec,
const uint32_t interval = (uint32_t) (clk*1000); // in msec
float Kang, Komg, KIang, Kyaw, Kdst, Kspd;
int16_t maxPwr;
float yawAngle=0.0;
float moveDestination, moveTarget;
float moveRate=0.0;
const float moveStep=0.2*clk;
int16_t fbBalance=0;
int16_t motorDeadband=0;
float mechFactR, mechFactL;
int8_t motorRDir=0, motorLDir=0;
bool spinContinuous=false;
float spinDest, spinTarget, spinFact=1.0;
float spinStep=0.0; //deg per 10msec
int16_t ipowerL=0, ipowerR=0;
int16_t motorLdir=0, motorRdir=0; //0:stop 1:+ -1:-
float vBatt, voltAve=3.7;
int16_t punchPwr, punchPwr2, punchDur, punchCountL=0, punchCountR=0;
byte demoMode=0;
void setup() {
pinMode(LED, OUTPUT);
digitalWrite(LED, HIGH);
Serial.begin(115200);
M5.begin();
Wire.begin(0, 26); //SDA,SCL
imuInit();
M5.Axp.ScreenBreath(11);
M5.Lcd.setRotation(2);
M5.Lcd.setTextFont(4);
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setTextSize(1);
resetMotor();
resetPara();
punchPwr2=max(punchPwr, motorDeadband);
resetVar();
calib1();
#ifdef DEBUG
debugSetup();
#else
setMode(false);
#endif
}
void loop() {
checkButtonP();
#ifdef DEBUG
if (debugLoop1()) return;
#endif
getGyro();
if (!standing) {
dispBatVolt();
aveAbsOmg = aveAbsOmg * 0.9 + abs(varOmg) * 0.1;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
M5.Lcd.setCursor(10,130);
M5.Lcd.printf("%5.2f ", -aveAccZ);
if (abs(aveAccZ)>0.9 && aveAbsOmg<1.5) {
calib2();
if (demoMode==1) startDemo();
M5.Axp.ScreenBreath(7);
standing=true;
}
}
else {
if (abs(varAng)>30.0 || counterOverPwr>maxOvp) {
resetMotor();
resetVar();
standing=false;
setMode(false);
M5.Axp.ScreenBreath(11);
}
else {
drive();
}
}
counter += 1;
if (counter >= 100) {
counter = 0;
dispBatVolt();
if (serialMonitor) sendStatus();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void calib1() {
calDelay(30);
digitalWrite(LED, LOW);
calDelay(80);
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setCursor(0, LCDV_MID);
M5.Lcd.print(" Cal-1 ");
gyroYoffset=0.0;
for (int i=0; i <N_CAL1; i++){
readGyro();
gyroYoffset += gyroYdata;
delay(9);
}
gyroYoffset /= (float)N_CAL1;
M5.Lcd.fillScreen(BLACK);
digitalWrite(LED, HIGH);
}
void calib2() {
resetVar();
resetMotor();
digitalWrite(LED, LOW);
calDelay(80);
M5.Lcd.setCursor(0, LCDV_MID);
M5.Lcd.println(" Cal-2 ");
accXoffset=0.0;
gyroZoffset=0.0;
for (int i=0; i <N_CAL2; i++){
readGyro();
accXoffset += accXdata;
gyroZoffset += gyroZdata;
delay(9);
}
accXoffset /= (float)N_CAL2;
gyroZoffset /= (float)N_CAL2;
M5.Lcd.fillScreen(BLACK);
digitalWrite(LED, HIGH);
}
void checkButtonP() {
byte pbtn=M5.Axp.GetBtnPress();
if (pbtn==2) calib1(); //short push
else if (pbtn==1) setMode(true); //long push
}
void calDelay(int n) {
for (int i=0; i<n; i++) {
getGyro();
delay(9);
}
}
void setMode(bool inc) {
if (inc) demoMode=++demoMode%2;
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setCursor(5, 5);
if (demoMode==0) M5.Lcd.print("Stand ");
else if (demoMode==1) M5.Lcd.print("Demo ");
}
void startDemo() {
moveRate=1.0;
spinContinuous=true;
spinStep=-40.0*clk;
}
void resetPara() {
Kang=35.0;
Komg=0.8;
KIang=700.0;
Kyaw=0.0;
Kdst=60.0;
Kspd=3.0;
mechFactL=0.7;
mechFactR=0.0;
punchPwr=25;
punchDur=1;
fbBalance=0;
motorDeadband=14;
maxPwr=127;
}
void getGyro() {
readGyro();
varOmg = (gyroYdata-gyroYoffset); //unit:deg/sec
yawAngle += (gyroZdata-gyroZoffset) * clk; //unit:g
varAng += (varOmg + ((accXdata-accXoffset) * 57.3 - varAng) * cutoff ) * clk; //complementary filter
}
void readGyro() {
float gX, gY, gZ, aX, aY, aZ;
M5.Imu.getGyroData(&gX,&gY,&gZ);
M5.Imu.getAccelData(&aX,&aY,&aZ);
gyroYdata=gX;
gyroZdata=-gY;
gyroXdata=-gZ;
accXdata=aZ;
accZdata=aY;
}
void drive() {
#ifdef DEBUG
debugDrive();
#endif
if (abs(moveRate)>0.1) spinFact=constrain(-(powerR+powerL)/10.0, -1.0, 1.0); //moving
else spinFact=1.0; //standing
if (spinContinuous) spinTarget += spinStep * spinFact;
else {
if (spinTarget < spinDest) spinTarget += spinStep;
if (spinTarget > spinDest) spinTarget -= spinStep;
}
moveTarget += moveStep * (moveRate +(float)fbBalance/100.0);
varSpd += power * clk;
varDst += Kdst * (varSpd * clk -moveTarget);
varIang += KIang * varAng * clk;
power = varIang + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 1000.0) counterOverPwr += 1;
else counterOverPwr =0;
if (counterOverPwr > maxOvp) return;
power = constrain(power, -maxPwr, maxPwr);
yawPower = (yawAngle - spinTarget) * Kyaw;
powerR = power - yawPower;
powerL = power + yawPower;
ipowerL = (int16_t) constrain(powerL * mechFactL, -maxPwr, maxPwr);
int16_t mdbn=-motorDeadband;
int16_t pp2n=-punchPwr2;
if (ipowerL > 0) {
if (motorLdir == 1) punchCountL = constrain(++punchCountL, 0, 100);
else punchCountL=0;
motorLdir = 1;
if (punchCountL<punchDur) drvMotorL(max(ipowerL, punchPwr2));
else drvMotorL(max(ipowerL, motorDeadband));
}
else if (ipowerL < 0) {
if (motorLdir == -1) punchCountL = constrain(++punchCountL, 0, 100);
else punchCountL=0;
motorLdir = -1;
if (punchCountL<punchDur) drvMotorL(min(ipowerL, pp2n));
else drvMotorL(min(ipowerL, mdbn));
}
else {
drvMotorL(0);
motorLdir = 0;
}
ipowerR = (int16_t) constrain(powerR * mechFactR, -maxPwr, maxPwr);
if (ipowerR > 0) {
if (motorRdir == 1) punchCountR = constrain(++punchCountR, 0, 100);
else punchCountR=0;
motorRdir = 1;
if (punchCountR<punchDur) drvMotorR(max(ipowerR, punchPwr2));
else drvMotorR(max(ipowerR, motorDeadband));
}
else if (ipowerR < 0) {
if (motorRdir == -1) punchCountR = constrain(++punchCountR, 0, 100);
else punchCountR=0;
motorRdir = -1;
if (punchCountR<punchDur) drvMotorR(min(ipowerR, pp2n));
else drvMotorR(min(ipowerR, mdbn));
}
else {
drvMotorR(0);
motorRdir = 0;
}
}
void drvMotorL(int16_t pwm) {
drvMotor(0, (int8_t)constrain(pwm, -127, 127));
}
void drvMotorR(int16_t pwm) {
drvMotor(1, (int8_t)constrain(-pwm, -127, 127));
}
void drvMotor(byte ch, int8_t sp) {
Wire.beginTransmission(0x38);
Wire.write(ch);
Wire.write(sp);
Wire.endTransmission();
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
counterOverPwr=0;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
moveRate=0.0;
spinContinuous=false;
spinDest=0.0;
spinTarget=0.0;
spinStep=0.0;
yawAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
}
void sendStatus () {
Serial.print(millis()-time0);
Serial.print(" stand="); Serial.print(standing);
Serial.print(" accX="); Serial.print(accXdata);
Serial.print(" power="); Serial.print(power);
Serial.print(" ang=");Serial.print(varAng);
Serial.print(", ");
Serial.print(millis()-time0);
Serial.println();
}
void imuInit() {
M5.Imu.Init();
if (M5.Imu.imuType=M5.Imu.IMU_MPU6886) {
M5.Mpu6886.SetGyroFsr(M5.Mpu6886.GFS_250DPS); //250DPS 500DPS 1000DPS 2000DPS
M5.Mpu6886.SetAccelFsr(M5.Mpu6886.AFS_4G); //2G 4G 8G 16G
if (serialMonitor) Serial.println("MPU6886 found");
}
else if (serialMonitor) Serial.println("MPU6886 not found");
}
void dispBatVolt() {
M5.Lcd.setCursor(5, LCDV_MID);
vBatt= M5.Axp.GetBatVoltage();
M5.Lcd.printf("%4.2fv ", vBatt);
}
view raw BalaCv26c.ino hosted with ❤ by GitHub

2020年6月9日火曜日

BalaC Balancing Robot

Sorry for the spaghetti code...


//
// BalaC balancing robot (IMU:MPU6886)
// by Kiraku Labo
//
// 1. Lay the robot flat, and power on.
// 2. Wait until Gal-1 (Pitch Gyro calibration) completes.
// 3. Hold still the robot upright in balance until Cal-2 (Accel & Yaw Gyro cal) completes.
//
// short push of power button: Gyro calibration
// long push (>1sec) of power button: switch mode between standig and demo(circle)
//
#include <M5StickC.h>
#define LED 10
#define N_CAL1 100
#define N_CAL2 100
#define LCDV_MID 60
boolean serialMonitor=true;
boolean standing=false;
int16_t counter=0;
uint32_t time0=0, time1=0;
int16_t counterOverPwr=0, maxOvp=20;
float power, powerR, powerL, yawPower;
float varAng, varOmg, varSpd, varDst, varIang;
float gyroXoffset, gyroYoffset, gyroZoffset, accXoffset;
float gyroXdata, gyroYdata, gyroZdata, accXdata, accZdata;
float aveAccX=0.0, aveAccZ=0.0, aveAbsOmg=0.0;
float cutoff=0.1; //~=2 * pi * f (Hz)
const float clk = 0.01; // in sec,
const uint32_t interval = (uint32_t) (clk*1000); // in msec
float Kang, Komg, KIang, Kyaw, Kdst, Kspd;
int16_t maxPwr;
float yawAngle=0.0;
float moveDestination, moveTarget;
float moveRate=0.0;
const float moveStep=0.2*clk;
int16_t fbBalance=0;
int16_t motorDeadband=0;
float mechFactR, mechFactL;
int8_t motorRDir=0, motorLDir=0;
bool spinContinuous=false;
float spinDest, spinTarget, spinFact=1.0;
float spinStep=0.0; //deg per 10msec
int16_t ipowerL=0, ipowerR=0;
int16_t motorLdir=0, motorRdir=0; //0:stop 1:+ -1:-
float vBatt, voltAve=3.7;
int16_t punchPwr, punchPwr2, punchDur, punchCountL=0, punchCountR=0;
byte demoMode=0;
void setup() {
pinMode(LED, OUTPUT);
digitalWrite(LED, HIGH);
Serial.begin(115200);
M5.begin();
Wire.begin(0, 26); //SDA,SCL
imuInit();
M5.Axp.ScreenBreath(11);
M5.Lcd.setRotation(2);
M5.Lcd.setTextFont(4);
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setTextSize(1);
resetMotor();
resetPara();
resetVar();
calib1();
#ifdef DEBUG
debugSetup();
#else
setMode(false);
#endif
}
void loop() {
checkButtonP();
#ifdef DEBUG
if (debugLoop1()) return;
#endif
getGyro();
if (!standing) {
dispBatVolt();
aveAbsOmg = aveAbsOmg * 0.9 + abs(varOmg) * 0.1;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
M5.Lcd.setCursor(10,130);
M5.Lcd.printf("%5.2f ", -aveAccZ);
if (abs(aveAccZ)>0.9 && aveAbsOmg<1.5) {
calib2();
if (demoMode==1) startDemo();
standing=true;
}
}
else {
if (abs(varAng)>30.0 || counterOverPwr>maxOvp) {
resetMotor();
resetVar();
standing=false;
setMode(false);
}
else {
drive();
}
}
counter += 1;
if (counter >= 100) {
counter = 0;
dispBatVolt();
if (serialMonitor) sendStatus();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void calib1() {
calDelay(30);
digitalWrite(LED, LOW);
calDelay(80);
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setCursor(0, LCDV_MID);
M5.Lcd.print(" Cal-1 ");
gyroYoffset=0.0;
for (int i=0; i <N_CAL1; i++){
readGyro();
gyroYoffset += gyroYdata;
delay(9);
}
gyroYoffset /= (float)N_CAL1;
M5.Lcd.fillScreen(BLACK);
digitalWrite(LED, HIGH);
}
void calib2() {
resetVar();
resetMotor();
digitalWrite(LED, LOW);
calDelay(80);
M5.Lcd.setCursor(0, LCDV_MID);
M5.Lcd.println(" Cal-2 ");
accXoffset=0.0;
gyroZoffset=0.0;
for (int i=0; i <N_CAL2; i++){
readGyro();
accXoffset += accXdata;
gyroZoffset += gyroZdata;
delay(9);
}
accXoffset /= (float)N_CAL2;
gyroZoffset /= (float)N_CAL2;
M5.Lcd.fillScreen(BLACK);
digitalWrite(LED, HIGH);
}
void checkButtonP() {
byte pbtn=M5.Axp.GetBtnPress();
if (pbtn==2) calib1(); //short push
else if (pbtn==1) setMode(true); //long push
}
void calDelay(int n) {
for (int i=0; i<n; i++) {
getGyro();
delay(9);
}
}
void setMode(bool inc) {
if (inc) demoMode=++demoMode%2;
M5.Lcd.fillScreen(BLACK);
M5.Lcd.setCursor(5, 5);
if (demoMode==0) M5.Lcd.print("Stand ");
else if (demoMode==1) M5.Lcd.print("Demo ");
}
void startDemo() {
moveRate=1.0;
spinContinuous=true;
spinStep=-40.0*clk;
}
void resetPara() {
Kang=37.0;
Komg=0.84;
KIang=800.0;
Kyaw=4.0;
Kdst=85.0;
Kspd=2.7;
mechFactL=0.45;
mechFactR=0.45;
punchPwr=20;
punchDur=1;
fbBalance=-3;
motorDeadband=10;
maxPwr=120;
punchPwr2=max(punchPwr, motorDeadband);
}
void getGyro() {
readGyro();
varOmg = (gyroYdata-gyroYoffset); //unit:deg/sec
yawAngle += (gyroZdata-gyroZoffset) * clk; //unit:g
varAng += (varOmg + ((accXdata-accXoffset) * 57.3 - varAng) * cutoff ) * clk; //complementary filter
}
void readGyro() {
float gX, gY, gZ, aX, aY, aZ;
M5.Imu.getGyroData(&gX,&gY,&gZ);
M5.Imu.getAccelData(&aX,&aY,&aZ);
gyroYdata=gX;
gyroZdata=-gY;
gyroXdata=-gZ;
accXdata=aZ;
accZdata=aY;
}
void drive() {
#ifdef DEBUG
debugDrive();
#endif
if (abs(moveRate)>0.1) spinFact=constrain(-(powerR+powerL)/10.0, -1.0, 1.0); //moving
else spinFact=1.0; //standing
if (spinContinuous) spinTarget += spinStep * spinFact;
else {
if (spinTarget < spinDest) spinTarget += spinStep;
if (spinTarget > spinDest) spinTarget -= spinStep;
}
moveTarget += moveStep * (moveRate +(float)fbBalance/100.0);
varSpd += power * clk;
varDst += Kdst * (varSpd * clk -moveTarget);
varIang += KIang * varAng * clk;
power = varIang + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 1000.0) counterOverPwr += 1;
else counterOverPwr =0;
if (counterOverPwr > maxOvp) return;
power = constrain(power, -maxPwr, maxPwr);
yawPower = (yawAngle - spinTarget) * Kyaw;
powerR = power - yawPower;
powerL = power + yawPower;
ipowerL = (int16_t) constrain(powerL * mechFactL, -maxPwr, maxPwr);
int16_t mdbn=-motorDeadband;
int16_t pp2n=-punchPwr2;
if (ipowerL > 0) {
if (motorLdir == 1) punchCountL = constrain(++punchCountL, 0, 100);
else punchCountL=0;
motorLdir = 1;
if (punchCountL<punchDur) drvMotorL(max(ipowerL, punchPwr2));
else drvMotorL(max(ipowerL, motorDeadband));
}
else if (ipowerL < 0) {
if (motorLdir == -1) punchCountL = constrain(++punchCountL, 0, 100);
else punchCountL=0;
motorLdir = -1;
if (punchCountL<punchDur) drvMotorL(min(ipowerL, pp2n));
else drvMotorL(min(ipowerL, mdbn));
}
else {
drvMotorL(0);
motorLdir = 0;
}
ipowerR = (int16_t) constrain(powerR * mechFactR, -maxPwr, maxPwr);
if (ipowerR > 0) {
if (motorRdir == 1) punchCountR = constrain(++punchCountR, 0, 100);
else punchCountR=0;
motorRdir = 1;
if (punchCountR<punchDur) drvMotorR(max(ipowerR, punchPwr2));
else drvMotorR(max(ipowerR, motorDeadband));
}
else if (ipowerR < 0) {
if (motorRdir == -1) punchCountR = constrain(++punchCountR, 0, 100);
else punchCountR=0;
motorRdir = -1;
if (punchCountR<punchDur) drvMotorR(min(ipowerR, pp2n));
else drvMotorR(min(ipowerR, mdbn));
}
else {
drvMotorR(0);
motorRdir = 0;
}
}
void drvMotorL(int16_t pwm) {
drvMotor(0, (int8_t)constrain(pwm, -127, 127));
}
void drvMotorR(int16_t pwm) {
drvMotor(1, (int8_t)constrain(-pwm, -127, 127));
}
void drvMotor(byte ch, int8_t sp) {
Wire.beginTransmission(0x38);
Wire.write(ch);
Wire.write(sp);
Wire.endTransmission();
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
counterOverPwr=0;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
moveRate=0.0;
spinContinuous=false;
spinDest=0.0;
spinTarget=0.0;
spinStep=0.0;
yawAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
}
void sendStatus () {
Serial.print(millis()-time0);
Serial.print(" stand="); Serial.print(standing);
Serial.print(" accX="); Serial.print(accXdata);
Serial.print(" power="); Serial.print(power);
Serial.print(" ang=");Serial.print(varAng);
Serial.print(", ");
Serial.print(millis()-time0);
Serial.println();
}
void imuInit() {
M5.Imu.Init();
if (M5.Imu.imuType=M5.Imu.IMU_MPU6886) {
M5.Mpu6886.SetGyroFsr(M5.Mpu6886.GFS_250DPS); //250DPS 500DPS 1000DPS 2000DPS
M5.Mpu6886.SetAccelFsr(M5.Mpu6886.AFS_4G); //2G 4G 8G 16G
if (serialMonitor) Serial.println("MPU6886 found");
}
else if (serialMonitor) Serial.println("MPU6886 not found");
}
void dispBatVolt() {
M5.Lcd.setCursor(5, LCDV_MID);
vBatt= M5.Axp.GetBatVoltage();
M5.Lcd.printf("%4.2fv ", vBatt);
}
view raw BalaCv25.ino hosted with ❤ by GitHub

2020年5月16日土曜日

ESP32で古時計の精度改善


ソースコードは、重力振り子用の構成になっています。
//*** WIFI SETTING の下2行がWiFiのSSIDとパスコードの設定部分です。

EPS32がインストールされているArduino IDEで、ボードとして「WEMOS LOLIN32」を選択してコンパイルします。

起動後、OLEDに表示されるIPアドレスに、ブラウザ(ChromeとFireFox以外は試してないです)からアクセスし、「Config」メニューの「Pendulum XX cycles = YY sec」で時計のギヤ比(YY秒間で振り子がXX回往復)を、「Pend Cycle between Tune: ZZ」で修正間隔(振り子ZZ回往復ごとにコイル電流を更新、1分に1回程度で良いと思います)を設定して「Apply」し、再度「Config」から「Reboot」すれば、とりあえずは動くはずです。


回転振り子については、#define GRAVITYをコメントアウトし、#define TORSIONを生かしてコンパイルします。センサーの設置位置などが微妙で、条件が変わるとソースコード中の定数の調整も必要と思われます。


//
// Automatic Clock Tuner
// by Kiraku Labo
//
#include <SPIFFS.h>
#include <WiFiUdp.h>
#include <HTTPClient.h>
#include <ArduinoOTA.h>
#include <ESPAsyncWebServer.h>
#include <AsyncTCP.h>
#include <SSD1306Wire.h>
#include <WiFi.h>
#define GRAVITY //Gravity pendulum clock
//#define TORSION //Torsion pendulum clock
#define TZ_STR0 "JST-9"
#define TZ_STR1 "CET-1CEST-2,M3.5.0/02:00:00,M10.5.0/03:00:00"
#define TZ_STR2 "CST6CDT5,M3.2.0/02:00:00,M11.1.0/02:00:00"
#define TZ_STR3 "NZST-12NZDT-13,M9.5.0/02:00:00,M4.1.0/2:00:00"
#ifdef GRAVITY
#define DISP_INVERTED
#define L9110
#define A3144 //Mag sensor (Hall)
#define DEFAULT_PEND_CYCLE 748 //PEND_CYCLE pendulum cycles per PEND_DUR seconds
#define DEFAULT_PEND_DUR 735
#define DEFAULT_TUNE_CYCLE 60
#define DEFAULT_PEND_LF 1 //lift factor
#define DEFAULT_KP 900
#define DEFAULT_KI 200
#endif
#ifdef TORSION
#define DISP_INVERTED
#define L9110
#define HMC5883 //Mag sensor (Digital compass)
#define MAG_THRESH_H 3000
#define MAG_THRESH_L 2000
#define DEFAULT_PEND_CYCLE 1 //PEND_CYCLE pendulum cycles per PEND_DUR seconds
#define DEFAULT_PEND_DUR 10
#define DEFAULT_TUNE_CYCLE 15
#define DEFAULT_PEND_LF 270 //swing angle
#define DEFAULT_KP 250
#define DEFAULT_KI 50
#endif
#define DEFAULT_NTP_BY_NAME true
#define DEFAULT_STA_IP_FIX "0" //1:Fix 0:DNS
#define DEFAULT_DATE_FORMAT 1 //1:JP, 2:EU, 3:US
//*** WIFI SETTING
const char* DEFAULT_WIFI_SSID="xxxxxxxx";
const char* DEFAULT_WIFI_PASS="yyyyyyyy";
//***
const char* DEFAULT_STA_GW="192.168.0.1";
const char* DEFAULT_SUBNET="255.255.255.0";
const char* DEFAULT_STA_DNS="192.168.0.1";
const char* DEFAULT_NTP_IP="210.173.160.87";
const char* DEFAULT_NTP_NAME="ntp.nict.jp";
const char* DEFAULT_TZ_STR=TZ_STR0;
const char* DEFAULT_STA_IP="192.168.0.112";
const char* apSsid="cTune";
const char* apPass="12345678";
const String verLetter="V";
const String fileVer="A"+verLetter; //if file ver is different, load default setting
const String project="cTune";
const String verNum="323p";
#define DEFAULT_NTP_MIN_INTERVAL 3 //minute
#define DEFAULT_NTP_MAX_INTERVAL 60 //minute
#ifdef HMC5883
#define MAX_NTP_TIMEOUT 1000 //msec
#else
#define MAX_NTP_TIMEOUT 3000 //msec
#endif
#define INITIAL_NTP_VALID 100 //msec
#define N_NTP_IP_HISTORY 20
#define BUF_SIZE 200
#define N_NTP_HISTORY 300
#define PRE_CYCLE_MS 8000 //8 sec worth of cycles before setRef
#define N_HISTORY 1500
#define MIN_HEAP 15000
#define NUM_GRAPH_SPAN 1440 //points, must be less than N_HISTORY
#define NTP_PACKET_SIZE 48
#define SEVENTY_YEARS 2208988800UL
#define SCREEN_W 128
#define SCREEN_H 64
#define CENTER_W (SCREEN_W/2)
#define CHAR_W 8
#define CHAR_H 16
#define GTOP 33
#define GBOTTOM 63
#define GYCENTER 48 // y axis 0
#define GXORIGIN 2
#define GRAPH_W (SCREEN_W-GXORIGIN-3)
#define OLEDFONT ArialMT_Plain_16
#define CONFIG_FILE "/config.file"
#define G2_INTERVAL 15 //points
#define G2_THRESH 1500 //points
#define ADJ_MAX 1023 //must be 63 or more, see ##1
#define ADJ_MIN -1023
#define ONOFF_MODE_THRESH 500 //csec (1/100 sec), If difference is greater than this value, coil is driven in full power.
#define PRECISE_MODE_THRESH 100 //csec, In Onoff mode, when the error becomes within this range, Onoff mode ends.
#define ERROR_LIMIT -43200 //=12H If error (in sec) <this value (big delay), coil power is disabled
#define NTP_OFFSET_THRESH_H 20000 //usec
#define NTP_OFFSET_THRESH_L 10000 //usec
#define LIFT_SWING 100 //Lift Factor vs Swing Angle threshold
#define SENS_PIN 15
#define LED_PIN 13
#ifdef COIL_POLARITY
#define DRV1_PIN 14
#define DRV2_PIN 12
#else
#define DRV1_PIN 12
#define DRV2_PIN 14
#endif
#define SDA_PIN 5
#define SCL_PIN 4
#define DMARGIN 0
#define BTN_PIN 0
#define LED_ON HIGH
#define LED_OFF LOW
#if defined(A3144)
#define SENSOR_ON LOW
#define SENSOR_OFF HIGH
#else
#define SENSOR_ON HIGH
#define SENSOR_OFF LOW
#endif
#if defined(HMC5883)
#define MAG_ADDR 0x1E
#endif
struct tm tmAtRef0Local, tmAtSetTimeLocal, tmAtResetMMLocal, tmSynchLocal;
struct timeval tvAtNtpSuccess, tvAtSensTrig, tvAtRef0, tvAtResetMM, tvAtNtpFail, tvGmtNow, tvAtNtpServerSet;
struct timeval tvNtpRef, tvNtpOrig, tvNtpRecv, tvNtpTrans, tvStart, tvEnd;
int32_t ntpDelay, ntpOffset, ntpOffsetPerMin=0;
float ntpDelayAve=INITIAL_NTP_VALID*500;
boolean serialMon=false;
const String textHtml="text/html";
int32_t errorHistory[2][N_HISTORY]; //csec
int16_t adjHistory[2][N_HISTORY];
time_t tHistory[2][N_HISTORY]; //sec
time_t gmtLast=0, gmtAtSec=0, gmtNow;
int16_t adjLevel=0, adjLevelMax=0, adjLevelMin=0;
float cadjLevelAve=0.0;
int32_t numHistory[2]={-1, -1};
boolean adjOn=true;
boolean onoffMode=false;
boolean timeWasSynched=false, setRefReady=false;
int16_t adjGraphFactor=5*(ADJ_MAX+1)/64;
uint16_t ntpIPHistoryIdx=0;
uint16_t lcdGrAltSec=10;
volatile boolean refSet=false;
volatile int32_t countPend=0;
volatile boolean sensTrig=false; //, trigWindow=false;
volatile boolean sensRelease=false;
volatile int16_t pendDir=0;
volatile uint32_t milliSensLast=0, milliSensTrig=0, milliSensRelease=0, milliSensDur=0;
volatile int64_t csecPend=0;
char strBuf[BUF_SIZE];
byte packetBuffer[NTP_PACKET_SIZE];
boolean shortPush=false, longPush=false, longlongPush=false;
uint32_t buttonMilli=0;
time_t tLocal;
time_t tzStart=0, tzEnd=0;
int32_t tzOffset=0;
boolean tzDstObs=false;
int tzDst=0;
int32_t csecPendError=0, csecPendErrorMax=0, csecPendErrorMin=0, csecPendErrorLast=0;
int32_t cadjLevel=0;
uint32_t ntpTurnaround;
byte gSpanUnitIdx=1; //0:h 1:d 2:w
byte gYEscaleIdx=0;
byte gYCscaleIdx=0;
uint32_t graphSpan=24*3600; //in seconds
String gYEscaleMM, gYCscaleMM;
const uint32_t gSpanUnit[] = {3600, 3600*24, 24*7*3600};
const String gSpanUnitStr[] = {"h", "d", "w"};
const String gYEscaleStr[] = {"Auto", "1s", "5s ", "20s", "100s"};
const String gYCscaleStr[] = {"Auto", "20", "100", "500", "2000"};
const int16_t gYEscaleNum[] = {0,1,5,20,100};
const int16_t gYCscaleNum[] = {0,20,100,500,2000};
const int16_t ngY1scaleNum[] = {10,20,50,100};
byte ngY1scaleIdx=0;
int16_t gYEscale=0, gYCscale=0;
byte ntpPacketId=0;
byte ntpInvalidCount=0;
boolean ntpByName=DEFAULT_NTP_BY_NAME;
uint16_t countConsecutiveDec=0;
float pendPeriod;
int32_t partial0Start;
int32_t partial0End;
WiFiUDP udp;
HTTPClient http;
AsyncWebServer server(80);
SSD1306Wire oled(0x3c, SDA_PIN, SCL_PIN);
const IPAddress apSNM(255,255,255,0);
IPAddress staIP;
IPAddress staGateway;
IPAddress staSNM;
IPAddress staDNS;
IPAddress ntpIP;
IPAddress ntpIPbyIP;
IPAddress ntpIPHistory[N_NTP_IP_HISTORY];
time_t ntpIPTimeHistory[N_NTP_IP_HISTORY];
const String msgHead =
"<html><head><meta charset='UTF-8'><title>Kiraku Labo</title>\
<style>body{width:95%;margin:0;padding:30;background-color:#dddddd;text-align:center;font-size:36pt}\
h1{font-size:40pt} h2{font-size:36pt} p{font-size:36pt} button{font-size:50pt}\
input[type=submit]{font-size:50pt}\
input[type=radio]{width:50px;height:50px;vertical-align:middle}\
input[type=text]{width:500px;font-size:36pt;margin-right:50px}\
input[type=number]{width:130px;font-size:36pt;margin-right:0px}\
span{display:inline-block;width:350px;text-align:right}\
form{display:inline}</style>\
</head><body><h1>Kiraku Labo " + project + " " + verLetter+verNum +"</h1>";
String msgHome =
"<form action='CF'><input type='submit' value='Config'></form> \
<form action='SA'><input type='submit' value='Sens Adj'></form> \
<form action='MR'><input type='submit' value='Rst M/M'></form><br>\
<form action='H0'><input type='submit' value='Hand 0s'></form>\
<form action='EZ'><input type='submit' value='Err 0'></form>\
<form id='form2' action='SE'><button type='submit' form='form2'>Err +/-</button>\
<input id='EV' name='EV' type='number' step='0.1' value='0' style='font-size:50pt'>s</form><br>\
<form action='TC'><input type='submit' value='Tgl Ctrl'></form>\
<form id='form3' action='SO'><button type='submit' form='form3'>Set Current</button>\
<input id='OV' name='OV' type='number' value='0' max='1023' min='-1023' style='font-size:50pt;width:200px'></form><br>\
<form action='ST'><input type='submit' value='Home'></form> \
<form action='GR'><input type='submit' value='Accuracy'></form>";
const String msgEnd = "</body></html>";
const String msgYesNo= "<form action='YS'><input type='submit' value='Yes'></form>\
<form action='NO'><input type='submit' value=' No '>";
const String msgChartHead = "<canvas id='myChart' width='400' height='250'></canvas>\
<script src='https://cdnjs.cloudflare.com/ajax/libs/Chart.js/2.7.1/Chart.bundle.min.js'></script>\
<script>Chart.defaults.global.defaultFontSize=30;";
int32_t pendCycle, pendDur;
String msgConf;
String wifiSSID, wifiPass, ntpServerName, tzStr;
String strVer, strPC, strPD, strPT, strKP, strKI, strLF, strWS, strWP, strIF, strIL, strIG, strID, strIS, strNF, strNN, strNI, strNV, strNX, strTZ, strDF;
boolean staIpFixed=false, apOnly=false, wifiDefined=false;
byte dateFormat=0;
const String dateFmtYMD[4]={"%Y/%m/%d", "%Y/%m/%d", "%d/%m/%Y", "%m/%d/%Y"};
const String dateFmtMD[4]={"%m/%d", "%m/%d", "%d/%m", "%m/%d"};
const String dateStr[4]={"", "yyyy/mm/dd", "dd/mm/yyyy", "mm/dd/yyyy"};
volatile uint32_t microSensTrig=0;
volatile boolean sensAdjMode=false;
byte lcdGmode=0; //0:alternate, 1:error, 2:Current
int32_t ntpDelayLimitUs=INITIAL_NTP_VALID*1000;
int16_t magX, magY, magZ;
int32_t minSensOffDuration, minSensOnDuration, trigWindowSpan, pendWindow;
int16_t kP, kI, liftFactor;
int32_t preCount;
int32_t tuneInterval; //in sec
int32_t tuneIntervalMs; //in msec
int16_t pendTuneCycle; //cycles per tune
uint32_t pendPeriodMs;
int32_t secTmAdj, usecTmAdj;
int16_t ntpInterval, ntpMinInterval, ntpMaxInterval;
boolean ntpFirstOffset=true;
int32_t ntpInterporateAccum=0, ntpInterporateCount=0;
int64_t trigDelay=0;
uint32_t msecInterporate=0, msecNTP=0;
uint32_t msecTune=0;
uint32_t ntpSynchCount=0, ntpIntervalInc=0, ntpIntervalDec=0;
uint16_t ntpY1Scale=20, ntpY2Scale=200;
const int32_t gscaleE[]={10,20,50,100,200,500,1000,2000,5000,10000,20000,50000,100000,200000,500000}; //x0.01sec
const int16_t gscaleA[]={5,10,20,50,100,200,500,1000};
const int16_t numgE=sizeof(gscaleE)/sizeof(gscaleE[0]);
const int16_t numgA=sizeof(gscaleA)/sizeof(gscaleA[0]);
const uint32_t i2cTimeout=10; //msec
byte i2cStatus;
void (*funcPtrYes)(AsyncWebServerRequest *request)=NULL;
void (*funcPtrNo)(AsyncWebServerRequest *request)=NULL;
void (*funcPtrWeb)(AsyncWebServerRequest *request)=NULL;
AsyncWebServerRequest *funcReqWeb;
void sensInt() {
uint32_t milliAtInt=millis();
int16_t sns=digitalRead(SENS_PIN);
if (pendDir==0 && sns==SENSOR_ON && (milliAtInt-milliSensRelease)>minSensOffDuration) {
pendDir=1;
if (!sensAdjMode) ledOn();
sensTrig=true;
microSensTrig=micros();
milliSensTrig=milliAtInt;
if (refSet) {
countPend++;
csecPend=(int64_t)countPend * (int64_t)pendDur * 100 / (int64_t)pendCycle;
}
}
else if (pendDir==1 && sns==SENSOR_OFF && (milliAtInt-milliSensTrig)>minSensOnDuration) {
pendDir=0;
if (!sensAdjMode) ledOff();
sensRelease=true;
milliSensRelease=milliAtInt;
}
}
void setup() {
disableCore0WDT();
disableCore1WDT();
SPIFFS.begin(true);
Serial.begin(115200);
Wire.begin(SDA_PIN, SCL_PIN);
pinMode(BTN_PIN, INPUT_PULLUP);
pinMode(LED_PIN, OUTPUT);
ledOff();
setupOled();
#ifdef DISP_INVERTED
oled.flipScreenVertically();
#endif
oled.setTextAlignment(TEXT_ALIGN_LEFT);
Wire.setClock(50000); //external i2c 50khz
lcdDispText(0, 0, project+" "+verLetter+verNum);
#if defined(HMC5883)
setupHMC5883();
#endif
boolean errConfig=false;
if (SPIFFS.exists(CONFIG_FILE)) {
if (!loadConfigFile()) {
loadDefaultConfig();
errConfig=true;
}
}
else {
loadDefaultConfig();
errConfig=true;
}
setConfigPara();
setConfigMsg();
if (errConfig) saveConfigFile(); //saveConfigFile() destroys strXX
ntpInterval=ntpMinInterval;
setupMechTiming();
preCount=PRE_CYCLE_MS/pendPeriodMs;
if (preCount<3) preCount=3;
setupWifi();
setupServer();
while(!wifiConnected()); //if no wifi, infinite loop here
setupOta();
setupNtp();
int ret;
int32_t limit;
do {
limit=ntpDelayLimitUs;
ret=synchTime(1); //use transmit timestamp
lcdDispText(0,0, "E" + String(ret) + " TA=" + String(ntpTurnaround) + "/" + String(limit/1000) + " ");
delay(5000);
} while (ret!=0);
tvAtNtpServerSet=tvAtNtpSuccess;
ntpIPHistory[0]=ntpIP;
ntpIPTimeHistory[0]=tvAtNtpServerSet.tv_sec;
do {
limit=ntpDelayLimitUs;
ret=synchTime(0); //use offset
lcdDispText(0,0, "E" + String(ret) + " D=" + String(ntpDelay/1000) + "/" + String(limit/1000) + " ");
delay(5000);
} while (ret!=0);
updateNtpValidDelay();
setDst();
#if defined(HMC5883)
ledcSetup(1, 50000, 10); //LEDC_CHANNEL, LEDC_FREQUENCY, LEDC_RESOLUTION_BITS
ledcSetup(2, 50000, 10);
#else
ledcSetup(1, 100, 10); //LEDC_CHANNEL, LEDC_FREQUENCY, LEDC_RESOLUTION_BITS
ledcSetup(2, 100, 10);
#endif
ledcAttachPin(DRV1_PIN, 1); //PIN, LEDC_CHANNEL
ledcAttachPin(DRV2_PIN, 2);
drvCoil(0);
pinMode(SENS_PIN, INPUT_PULLUP);
#if !defined(HMC5883)
attachInterrupt(digitalPinToInterrupt(SENS_PIN), sensInt, CHANGE);
#endif
}
void loop() {
int sec;
#if defined(HMC5883)
getHMC5883();
if (sensAdjMode) dispMag();
int16_t magValue=abs16(magX)+abs16(magY)+abs16(magZ);
if (magValue>MAG_THRESH_H) magTrigH();
else if (magValue<MAG_THRESH_L) magTrigL();
#else
if (sensAdjMode) {
if (digitalRead(SENS_PIN)==SENSOR_ON) ledOn();
else ledOff();
}
#endif
if (sensTrig) {
sensTrig=false;
gettimeofday(&tvAtSensTrig, NULL);
#if !defined(HMC5883)
trigDelay=(int64_t)(micros()-microSensTrig);
if (trigDelay<0) trigDelay=0;
convUsec2Tv(convTv2Usec(&tvAtSensTrig) - trigDelay, &tvAtSensTrig);
#endif
pendIndicator(WHITE);
ledOn();
if (refSet) {
if (countPend%pendTuneCycle==0) {
updateError();
lcdDispError();
tune();
lcdDispGraph();
}
else {
updateError();
if (!sensAdjMode) {
lcdDispError();
lcdDispGraph();
}
}
}
if (preCount>=0) {
if (preCount==0) {
#ifdef HMC5883
sec=tvAtSensTrig.tv_sec%60;
if (sec>=1 && sec<26) {
preCount=-1;
setRef0();
tune();
}
#else
preCount=-1;
setRef0();
tune();
#endif
}
else preCount--;
}
if (refSet) lcdDispNum4n(0,0,countPend%pendTuneCycle);
}
else if (sensRelease) {
sensRelease=false;
pendIndicator(BLACK);
ledOff();
}
gettimeofday(&tvGmtNow, NULL);
gmtNow=tvGmtNow.tv_sec;
if (gmtNow>gmtLast) { //every 1 sec
gmtAtSec=gmtNow;
gmtLast=gmtNow;
sec=gmtNow%60;
if (preCount>0) lcdDispTime(0,0,1); //date & time
else lcdDispTime(5,0,2); //time only
if (millis()-milliSensTrig>pendWindow && refSet) {
tvAtSensTrig=tvGmtNow;
updateError();
if (!sensAdjMode) {
lcdDispError();
lcdDispGraph();
}
}
if (sec==30) {
if (wifiConnected()) {
if (gmtAtSec>=tvAtNtpSuccess.tv_sec + ntpInterval*60) {
if (millis()-msecNTP>30000) {
msecNTP=millis();
if (synchTime(0)==0) {
updateNtpValidDelay();
}
else if (!ntpFirstOffset) interporateTime();
}
}
else if (!ntpFirstOffset) interporateTime();
}
else WiFi.begin(wifiSSID.c_str(), wifiPass.c_str());
if (millis()-milliSensTrig>pendWindow && refSet) tune();
}
}
if (funcPtrWeb) {
funcPtrWeb(funcReqWeb);
funcPtrWeb=NULL;
}
if (liftFactor>=LIFT_SWING) { //partial drive anniversary clock
uint32_t msPd=millis()-milliSensTrig;
if (msPd>partial0Start && msPd<partial0End) {
drvCoil(0);
}
else {
drvCoil(adjLevel);
}
}
senseButton();
ArduinoOTA.handle();
yield();
}
void dispMag() {
char lcdbuf[13];
snprintf(lcdbuf, 19, "X= %s%05d", magX>=0?" ":"-", abs16(magX));
lcdDispText2(0,1, lcdbuf, 80);
snprintf(lcdbuf, 19, "Y= %s%05d", magY>=0?" ":"-", abs16(magY));
lcdDispText2(0,2, lcdbuf, 80);
snprintf(lcdbuf, 19, "Z= %s%05d", magZ>=0?" ":"-", abs16(magZ));
lcdDispText2(0,3, lcdbuf, 80);
// Serial.print(magX);Serial.print(",");Serial.print(magY);Serial.print(",");
// Serial.println(magZ);
}
int16_t abs16(int16_t x) {
if (x>=0) return x;
else return -x;
}
int32_t abs32(int32_t x) {
if (x>=0) return x;
else return -x;
}
int64_t abs64(int64_t x) {
if (x>=0) return x;
else return -x;
}
void setRef0() {
countPend=0;
refSet=true;
tvAtRef0=tvAtSensTrig;
localtime_r(&tvAtRef0.tv_sec, &tmAtRef0Local);
tvAtResetMM=tvAtRef0;
tmAtResetMMLocal=tmAtRef0Local;
numHistory[0]=0;
numHistory[1]=0;
tHistory[0][0]=tvAtRef0.tv_sec;
tHistory[1][0]=tvAtRef0.tv_sec;
milliSensLast=milliSensTrig;
csecPendError=0;
csecPendErrorLast=0;
adjLevelMax=0;
adjLevelMin=0;
csecPendErrorMax=0;
csecPendErrorMin=0;
sendStat();
}
void sendStat() {
milliSensDur=milliSensTrig-milliSensLast;
milliSensLast=milliSensTrig;
struct tm tl;
localtime_r(&tvAtSensTrig.tv_sec, &tl);
snprintf(strBuf, BUF_SIZE, "PEND:%02d/%02d %02d:%02d:%02d.%03d Intv=%04d Cnt=%d Hst=%d TrigD=%d Err=%.2f Out=%d Ave=%.2f",
tl.tm_mon+1, tl.tm_mday, tl.tm_hour, tl.tm_min, tl.tm_sec, tvAtSensTrig.tv_usec/1000,
milliSensDur, countPend, numHistory[0], (int32_t)trigDelay, (float)csecPendError/100.0, adjLevel, cadjLevelAve/100.0);
dbgPrintln(strBuf);
}
void pendIndicator(OLEDDISPLAY_COLOR color) {
oled.setColor(color);
oled.fillCircle(124, 25, 3);
oled.display();
}
void tune() {
numHistory[0]++;
int16_t idx=numHistory[0] % N_HISTORY;
if (adjOn) {
adjPend();
lcdDispNum4n(9,1,adjLevel);
}
csecPendErrorLast=csecPendError;
errorHistory[0][idx]=csecPendError;
if (!onoffMode) cadjLevelAve = cadjLevelAve * 0.97 + (float)cadjLevel * 0.03;
adjHistory[0][idx]=adjLevel;
tHistory[0][idx]=gmtAtSec;
if (numHistory[0]%G2_INTERVAL==0) {
numHistory[1]++;
int16_t idx2=numHistory[1] % N_HISTORY;
errorHistory[1][idx2]=csecPendError;
adjHistory[1][idx2]=adjLevel;
tHistory[1][idx2]=gmtAtSec;
}
sendStat();
}
void updateError() {
csecPendError=(int32_t)(csecPend - (100*(int64_t)(tvAtSensTrig.tv_sec-tvAtRef0.tv_sec) +(int64_t)(tvAtSensTrig.tv_usec-tvAtRef0.tv_usec)/10000));
if (csecPendError>csecPendErrorMax) {
csecPendErrorMax=csecPendError;
// sendStat();
}
if (csecPendError<csecPendErrorMin) {
csecPendErrorMin=csecPendError;
// sendStat();
}
}
void lcdDispError() {
lcdDispNumF(0,1, csecPendError);
}
void adjPend() {
msecTune=millis();
if (abs32(csecPendError)>ONOFF_MODE_THRESH) onoffMode=true;
if (onoffMode) {
if (csecPendError>PRECISE_MODE_THRESH) cadjLevel=ADJ_MIN*100/(liftFactor<LIFT_SWING?liftFactor:1);
else if (csecPendError<-PRECISE_MODE_THRESH) cadjLevel=ADJ_MAX*100;
else {
onoffMode=false;
cadjLevel=(int32_t)cadjLevelAve;
}
}
else {
int32_t cadjLevelDelta = (int32_t) ((csecPendError-csecPendErrorLast)*kP/tuneInterval + csecPendError*kI/100); //use per-min rate factor of 60/tuneInterval
cadjLevelDelta *= (ADJ_MAX+1)/64; //##1
cadjLevel = constrain(cadjLevel-cadjLevelDelta, ADJ_MIN*100/(liftFactor<LIFT_SWING?liftFactor:1), ADJ_MAX*100);
}
if (csecPendError<ERROR_LIMIT*100) cadjLevel=0;
adjLevel=cadjLevel/100;
if (liftFactor<LIFT_SWING) { //gravity pend
drvCoil(adjLevel);
}
if (adjLevel>adjLevelMax) adjLevelMax=adjLevel;
if (adjLevel<adjLevelMin) adjLevelMin=adjLevel;
}
void drvCoil(int16_t pwr) {
if (pwr>=0) {
ledcWrite(1, 0);
ledcWrite(2, pwr);
}
else {
ledcWrite(2, 0);
ledcWrite(1, -pwr);
}
}
void senseButton() {
int button=digitalRead(BTN_PIN);
if (button==LOW) {
if (shortPush==false) {
shortPush=true;
longPush=false;
longlongPush=false;
buttonMilli=millis();
}
else {
if (millis()-buttonMilli>1000) {
if (!longPush) { //disp WiFi status
longPush=true;
clearGraph();
if (WiFi.status()==WL_CONNECTED) lcdDispText(0,2, wifiSSID.c_str());
else lcdDispText(0,2, "WiFi NG ");
lcdDispText(0,3, WiFi.localIP().toString());
}
else if (millis()-buttonMilli>2000) {
if (!longlongPush) { //long long push
longlongPush=true;
}
}
}
}
}
else {
if (shortPush==true) {
shortPush=false;
if (!longPush && !longlongPush) { //short push = lcd graph mode
lcdGmode = (lcdGmode+1)%3;
}
}
}
}
int64_t convTv2Usec(struct timeval* tv) {
return (int64_t)(tv->tv_sec)*1000000 + (int64_t)(tv->tv_usec);
}
void convUsec2Tv(int64_t t, struct timeval* tv) {
tv->tv_sec=(time_t)(t/1000000);
tv->tv_usec=(uint32_t)(t%1000000);
}
int synchTime(byte synchMode) { //syncMode 0= use offset, 1=use Transmit timestamp
struct timeval tv1, tv2;
int ret=getNTPTime(synchMode);
if (ret==0) { //validity is OK
if (synchMode==1) { //transfer
settimeofday(&tvNtpTrans, NULL);
tvAtNtpSuccess=tvNtpTrans;
}
else if (synchMode==0) { //offset mode
ntpSynchCount++;
if (ntpFirstOffset) {
ntpInterval=ntpMinInterval;
ntpOffset /= ntpInterval;
ntpOffsetPerMin=ntpOffset;
ntpDelayAve=(float)ntpDelay;
ntpFirstOffset=false;
}
else {
int16_t increment;
ntpOffsetPerMin=(ntpInterporateAccum+ntpOffset)/(ntpInterporateCount+1);
if (abs32(ntpOffset)<NTP_OFFSET_THRESH_L*3 && abs32(ntpOffsetPerMin)<NTP_OFFSET_THRESH_L) {
increment=ntpInterval*3/10;
if (increment==0) increment=1;
ntpIntervalInc++;
countConsecutiveDec=0;
}
else if (abs32(ntpOffset)>=NTP_OFFSET_THRESH_H*3 || abs32(ntpOffsetPerMin)>=NTP_OFFSET_THRESH_H) {
increment=-ntpInterval*3/13;
if (increment==0) increment=-1;
ntpIntervalDec++;
countConsecutiveDec++;
if (countConsecutiveDec>=3 && ntpByName) ntpChange();
}
else {
increment=0;
countConsecutiveDec=0;
}
ntpInterval += increment;
if (ntpInterval>ntpMaxInterval) ntpInterval=ntpMaxInterval;
if (ntpInterval<ntpMinInterval) ntpInterval=ntpMinInterval;
if (ntpInterval<=0) ntpInterval=1;
dbgPrintln("NTP interval+=" + String(increment) + " =" + String(ntpInterval) + " InterporateCt=" + String(ntpInterporateCount) + " Offset=" + String(ntpOffset/1000) + "ms"); //$$$$$
ntpInterporateCount=0;
ntpInterporateAccum=0;
}
gettimeofday(&tv1, NULL);
convUsec2Tv(convTv2Usec(&tv1) + +ntpOffset + ntpOffsetPerMin, &tv2); //##2
settimeofday(&tv2, NULL);
tvAtNtpSuccess=tv2;
}
if (timeWasSynched==false) {
timeWasSynched=true;
}
}
else {
gettimeofday(&tvAtNtpFail, NULL);
if (ntpInvalidCount>=3) {
if (ntpDelayLimitUs*2<MAX_NTP_TIMEOUT*1000) ntpDelayLimitUs *= 2;
else ntpDelayLimitUs=MAX_NTP_TIMEOUT*1000;
if (ntpByName) {
if (ntpInvalidCount>=6) {
ntpInvalidCount=0;
ntpIntervalInc=0;
ntpIntervalDec=0;
ntpDelayLimitUs=INITIAL_NTP_VALID*1000;
ntpChange();
}
}
}
}
localtime_r(&tv1.tv_sec, &tmSynchLocal);
snprintf(strBuf, BUF_SIZE, "NTP:%d.%d.%d.%d PID=%03d Code=%d Settime=%02d/%02d %02d:%02d:%02d.%06d offset=%d offset/min=%d delay=%d delayAve=%.2f %s",
ntpIP[0], ntpIP[1], ntpIP[2], ntpIP[3], ntpPacketId, ret, tmSynchLocal.tm_mon+1, tmSynchLocal.tm_mday, tmSynchLocal.tm_hour, tmSynchLocal.tm_min,
tmSynchLocal.tm_sec, tv1.tv_usec, ntpOffset, ntpOffsetPerMin, ntpDelay, ntpDelayAve, ret==0?"Synch Success":"Validity Fail");
dbgPrintln(strBuf);
return ret;
}
int getNTPTime(byte synchMode) {
int16_t pktSize;
if (udp.parsePacket()>0) udp.read(packetBuffer, NTP_PACKET_SIZE); //clear buffer
ntpPacketId++;
if (ntpPacketId==0) ntpPacketId=1; //1 to 255 are used
uint32_t msec=millis();
gettimeofday(&tvStart, NULL);
sendNTPpacket(); // send an NTP packet to a time server
do {
pktSize = udp.parsePacket();
ntpTurnaround=millis()-msec;
} while (pktSize<NTP_PACKET_SIZE && ntpTurnaround<MAX_NTP_TIMEOUT);
if (pktSize>0) udp.read(packetBuffer, NTP_PACKET_SIZE); // read the packet into the buffer
gettimeofday(&tvEnd, NULL);
getNtpTv(32, &tvNtpRecv);
getNtpTv(40, &tvNtpTrans);
int64_t t1=convTv2Usec(&tvStart);
int64_t t2=convTv2Usec(&tvNtpRecv);
int64_t t3=convTv2Usec(&tvNtpTrans);
int64_t t4=convTv2Usec(&tvEnd);
ntpOffset = (int32_t)( t2 - t1 + t3 - t4 )/2;
ntpDelay = (int32_t)((t4 - t1) - (t3 - t2));
if (ntpTurnaround>=MAX_NTP_TIMEOUT) {
ntpInvalidCount++;
return 2;
}
else if ((synchMode==0?ntpDelay/1000:ntpTurnaround)>=ntpDelayLimitUs/1000) { //##3
ntpInvalidCount++;
return 1;
}
else if (packetBuffer[31]!=ntpPacketId) return 3; //packet ID not match
else if (tvNtpTrans.tv_sec>2082726000UL) return 4; //if tv_sec>2036/1/1 do not record (NTP overflows in this year)
else {
ntpInvalidCount=0;
return 0;
}
}
void ntpChange() {
IPAddress temp=ntpIP;
if (ntpByName) WiFi.hostByName(ntpServerName.c_str(), ntpIP);
else ntpIP=ntpIPbyIP;
if (temp[0]==ntpIP[0] && temp[1]==ntpIP[1] && temp[2]==ntpIP[2] && temp[3]==ntpIP[3]) return;
gettimeofday(&tvAtNtpServerSet, NULL);
ntpFirstOffset=true;
ntpInterval=ntpMinInterval;
countConsecutiveDec=0;
ntpIPHistoryIdx++;
ntpIPHistory[ntpIPHistoryIdx%N_NTP_IP_HISTORY]=ntpIP;
ntpIPTimeHistory[ntpIPHistoryIdx%N_NTP_IP_HISTORY]=tvAtNtpServerSet.tv_sec;
}
void updateNtpValidDelay() {
ntpDelayAve = ntpDelayAve * 0.8 + 0.2*(float)ntpDelay;
ntpDelayLimitUs=(int32_t)(ntpDelayAve*2.0);
if (ntpDelayLimitUs>MAX_NTP_TIMEOUT*1000) ntpDelayLimitUs=MAX_NTP_TIMEOUT*1000;
}
void interporateTime() {
if (ntpMinInterval>ntpMaxInterval) return; //no interporation
if (millis()-msecInterporate<30000) return;
msecInterporate=millis();
struct timeval tv1, tv2;
delay(10); //prevent sec going back
gettimeofday(&tv1, NULL);
convUsec2Tv(convTv2Usec(&tv1) + ntpOffsetPerMin, &tv2);
settimeofday(&tv2, NULL);
ntpInterporateCount++;
ntpInterporateAccum+=ntpOffsetPerMin;
dbgPrintln("Time interporation:" + String(ntpInterporateCount) + " present usec=" + String(tv1.tv_usec) + " adj=" + String(ntpOffsetPerMin) + "usec");
}
void getNtpTv(int adr, struct timeval* tvp) {
uint32_t secSince1900 = packetBuffer[adr+0]<<24 | packetBuffer[adr+1]<<16 | packetBuffer[adr+2]<<8 | packetBuffer[adr+3];
tvp->tv_sec =secSince1900 - SEVENTY_YEARS;
tvp->tv_usec = (uint32_t)packetBuffer[adr+4]*1000000/256 + (uint32_t)packetBuffer[adr+5]*1000000/65536 +
(uint32_t)packetBuffer[adr+6]*1000000/65536/256;
}
void sendNTPpacket(){
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;
packetBuffer[47] = ntpPacketId; //Transmit timestamp
udp.beginPacket(ntpIP, 123);
udp.write(packetBuffer, NTP_PACKET_SIZE);
udp.endPacket();
}
void setDst() {
setenv("TZ", tzStr.c_str(), 1);
tzset();
String s=String(tzname[0]);
if (tzStr.indexOf(',')==-1) {
tzDstObs=false;
lcdDispText(0,3, "DST not observed");
}
else {
tzDstObs=true;
s+= "/"+String(tzname[1]);
}
lcdDispText(0,2, "TZ="+s + " ");
}
void connectWifi() {
uint32_t milli;
lcdDispText(0,1,"");
clearGraph();
lcdDispText(0,2, wifiSSID);
WiFi.disconnect(true);
WiFi.config(0u, 0u, 0u); //clear static IP
if (staIpFixed) WiFi.config(staIP, staGateway, staSNM, staDNS);
if (wifiSSID.length()>0) {
WiFi.begin(wifiSSID.c_str(), wifiPass.c_str());
milli=millis();
int16_t st;
do {
st=WiFi.status();
delay(20);
} while (st!= WL_CONNECTED && millis()-milli<15000);
if (st==WL_CONNECTED) {
lcdDispText(12,2, " OK");
lcdDispText(0,3, WiFi.localIP().toString());
delay(5000);
}
else {
lcdDispText(12,2, " NG");
delay(1000);
}
}
}
void setupWifi() {
byte tryCount=0;
WiFi.mode(WIFI_OFF);
WiFi.mode(WIFI_STA);
do {
connectWifi();
tryCount++;
} while(wifiConnected()==false && tryCount<3);
if (!wifiConnected()) {
apOnly=true;
WiFi.mode(WIFI_AP);
WiFi.softAP(apSsid, apPass);
lcdDispText(0,0, F("AP Only "));
lcdDispText(0,1, apSsid);
lcdDispText(0,2, apPass);
lcdDispText(0,3, WiFi.softAPIP().toString());
}
}
void setupNtp() {
if (ntpByName) {
lcdDispText(0,2, ntpServerName);
WiFi.hostByName(ntpServerName.c_str(), ntpIP);
}
else {
lcdDispText(0,2, "NTP by IP ");
ntpIP=ntpIPbyIP;
}
ntpFirstOffset=true;
lcdDispText(0,3, ntpIP.toString());
delay(4000);
}
boolean wifiConnected() {
if (WiFi.status()==WL_CONNECTED) return true;
else return false;
}
void dbgPrint(String s) {
if (serialMon) Serial.print(s);
}
void dbgPrintln(String s) {
dbgPrint(s+F("\r\n"));
}
void handleNotFound(AsyncWebServerRequest *request){
request->send(404, "text/plain", F("File Not Found\n\n"));
}
void dispStatus(AsyncWebServerRequest *request) {
String fmt=dateFmtMD[dateFormat] + " %H:%M:%S.";
struct tm tim;
struct timeval tv;
char buf[40]={0};
String s= msgHead + msgHome +
"<p>Pendulum Count=" + String(countPend) + " History=" + String(numHistory[0]) +
"<br>Error=" + csecToSecF(csecPendError) + " [" + csecToSecF(csecPendErrorMin) + ", " + csecToSecF(csecPendErrorMax) + "] sec" +
"<br>Current=" + String(adjLevel) + " [" + String(adjLevelMin) + ", " + String(adjLevelMax) + "] Ave=" + String(cadjLevelAve/100.0) +
"<br>Local IP=" + WiFi.localIP().toString() + "<br>NTP IP=" + ntpIP.toString() + (ntpByName?" (Pool)":"") +
"<br>Control Enabled=" + adjOn + " OnOff Mode=" + onoffMode +
"<br>Sensor: Min Off=" + String(minSensOffDuration) + " Min On=" + String(minSensOnDuration) + " msec" +
"<br>Penddulum window=" + String(pendWindow) + " msec";
strftime(buf, 20, fmt.c_str(), &tmAtRef0Local);
s+= "<br>Reference 0=" + String(buf) + preZero3(tvAtRef0.tv_usec/1000);
strftime(buf, 20, fmt.c_str(), &tmAtResetMMLocal);
s+= "<br>M/M. Reset=" + String(buf) + preZero3(tvAtResetMM.tv_usec/1000);
gettimeofday(&tv, NULL);
localtime_r(&tv.tv_sec, &tim);
strftime(buf, 20, fmt.c_str(), &tim);
s+= "<br>Now=" + String(buf) + preZero3(tv.tv_usec/1000);
"</p>" + msgEnd;
request->send (200, textHtml, s);
}
String csecToSecF(int32_t csec) {
String s;
if (csec<0) s="-";
else s="";
return s + String(abs32(csec)/100) + "." + preZero2((int)(abs32(csec)%100));
}
String preZero2(int n) {
String s=String(n);
if (s.length()==1) return "0"+s;
else return s;
}
String preZero3(int n) {
String s=String(n);
int len=s.length();
if (len==1) return "00"+s;
else if (len==2) return "0"+s;
else return s;
}
void hand0Sec(AsyncWebServerRequest *request) {
String st;
if (!refSet) {
st=F("<h2>Time Ref not set</h2>");
request->send (200, textHtml, msgHead + msgHome + st + msgEnd);
}
else {
funcPtrYes=hand0SecExe;
funcPtrNo=dispStatus;
st=F("<h2>Set 0 second?</h2>");
request->send (200, textHtml, msgHead + st + msgYesNo + msgEnd);
}
}
void hand0SecExe(AsyncWebServerRequest *request) {
struct tm tl;
struct timeval tv;
gettimeofday(&tv, NULL);
localtime_r(&tv.tv_sec, &tl);
time_t secDiff;
if (tl.tm_sec>40) secDiff=60-tl.tm_sec; //Clock hand ahead
else secDiff=-tl.tm_sec; //Clock hand behind
if (tvAtRef0.tv_usec<tv.tv_usec) tvAtRef0.tv_sec -= 1;
tvAtRef0.tv_sec += secDiff;
tvAtRef0.tv_usec -= tv.tv_usec;
updateError();
csecPendErrorLast=csecPendError;
String st="<h2>Ref0 adjusted</h2>";
request->send (200, textHtml, msgHead + msgHome + st + msgEnd);
}
void resetMinMax(AsyncWebServerRequest *request) {
funcPtrYes=resetMinMaxExe;
funcPtrNo=dispStatus;
String st=F("<h2>Reset Min/Max for Error and Adj level?</h2>");
request->send (200, textHtml, msgHead + st + msgYesNo + msgEnd);
}
void resetMinMaxExe(AsyncWebServerRequest *request) {
adjLevelMax=adjLevel;
adjLevelMin=adjLevel;
csecPendErrorMax=csecPendError;
csecPendErrorMin=csecPendError;
gettimeofday(&tvAtResetMM, NULL);
localtime_r(&tvAtResetMM.tv_sec, &tmAtResetMMLocal);
String st= "<h2> Error M/M=" + csecToSecF(csecPendError) + " Adj M/M=" + String(adjLevel) + "</h2>";
request->send(200, textHtml, msgHead + msgHome + st + msgEnd);
}
void zeroError(AsyncWebServerRequest *request) {
funcPtrYes=zeroErrorExe;
funcPtrNo=dispStatus;
String st=F("<h2>Error set to 0?</h2>");
request->send (200, textHtml, msgHead + st + msgYesNo + msgEnd);
}
void zeroErrorExe(AsyncWebServerRequest *request) {
time_t secErr = csecPendError/100;
int32_t usecErr = (csecPendError%100)*10000;
int32_t temp=tvAtRef0.tv_usec - usecErr;
int32_t carry=0;
if (temp>=1000000) {
temp -= 1000000;
carry=1;
}
else if (temp<0) {
temp += 1000000;
carry=-1;
}
tvAtRef0.tv_usec=temp;
tvAtRef0.tv_sec+=carry-secErr;
updateError();
csecPendErrorLast=csecPendError;
String st=F("<h2>Ref0 adjusted and Error set to 0</h2>");
request->send (200, textHtml, msgHead + msgHome + st + msgEnd);
}
void graphError(AsyncWebServerRequest *request) {
char buf[20]={0};
struct tm tsl, tel;
time_t tEnd=time(NULL);
time_t tStart=tEnd-graphSpan;
byte dataSet;
String sel;
gYCscaleMM="suggestedMin:-30, suggestedMax:30";
String msgG = "<form action='GU' name='formGU' onchange='changeVal()'>";
msgG += "X:<select name='XS' style='font-size:50pt;width:110px;margin:0px'>";
for (byte i=1; i<=24; i++) {
sel=(graphSpan/gSpanUnit[gSpanUnitIdx]==i)?"selected":"";
msgG += "<option " + sel + " value='" + String(i) + "'>" + String(i) + "</option>";
}
msgG += "</select><select name='XU' style='font-size:50pt;width:100px;margin:0px'>";
for (byte i=0; i<3; i++) {
sel=(gSpanUnitIdx==i)?"selected":"";
msgG += "<option " + sel + " value='" + String(i) + "'>" + gSpanUnitStr[i] + "</option>";
}
msgG += "</select>&nbsp;&nbsp;A:<select name='YE' style='font-size:50pt;width:200px;margin:0px'>";
for (byte i=0; i<5; i++) {
sel=(gYEscaleIdx==i)?"selected":"";
msgG += "<option " + sel + " value='" + String(i) + "'>" + gYEscaleStr[i] + "</option>";
}
msgG += "</select>&nbsp;&nbsp;C:<select name='YC' style='font-size:50pt;width:200px'>";
for (byte i=0; i<5; i++) {
sel=(gYCscaleIdx==i)?"selected":"";
msgG += "<option " + sel + " value='" + String(i) + "'>" + gYCscaleStr[i] + "</option>";
}
msgG += "</select><br><input type='submit' value='Reload'></form> \
<form action='MM'><input type='submit' value='Home'></form>";
if (gYEscaleIdx==0) gYEscaleMM="suggestedMin:-5, suggestedMax:5";
else gYEscaleMM="min:-" + String(gYEscale) + ", max:" + String(gYEscale);
if (gYCscaleIdx==0) gYCscaleMM="suggestedMin:-500, suggestedMax:500";
else gYCscaleMM="min:-" + String(gYCscale) + ", max:" + String(gYCscale);
if (numHistory[0]<N_HISTORY) dataSet=0;
else if (tHistory[0][(numHistory[0]+1)%N_HISTORY]<tStart) dataSet=0;
else dataSet=1;
int32_t hEnd=numHistory[dataSet];
int32_t hStart;
if (graphSpan>14*24*3600) { //longest
if (numHistory[dataSet]<N_HISTORY) hStart=0;
else hStart=hEnd-N_HISTORY;
}
else {
int16_t count=N_HISTORY;
if (numHistory[dataSet]<N_HISTORY) count=numHistory[dataSet]+1;
hStart=hEnd;
for (int16_t i=0; i<count; i++) {
if (tHistory[dataSet][(N_HISTORY+hEnd-i)%N_HISTORY]<tStart) break;
hStart=hEnd-i;
}
}
tStart=tHistory[dataSet][hStart%N_HISTORY];
String outData = "[";
String errData = "[";
String secLabel="[";
for (int32_t i=hStart; i<=hEnd; i++) {
int32_t j=i%N_HISTORY;
outData += String(adjHistory[dataSet][j]) + ",";
errData += String(errorHistory[dataSet][j]) + ",";
secLabel += String(tHistory[dataSet][j]-tStart) + ",";
if ((int)esp_get_free_heap_size()<MIN_HEAP) break;
}
outData += "];";
errData += "];";
secLabel += "];";
localtime_r(&tStart, &tsl);
strftime(buf, 20, (dateFmtMD[dateFormat] + " %H:%M").c_str(), &tsl);
String stgT = "<br>" + verLetter+verNum + " From "+ buf + " Dataset " + String(dataSet);
String stg = msgChartHead;
stg += "var ctx = document.getElementById('myChart').getContext('2d');";
stg += "var errData=" + errData;
stg += "var outData=" + outData;
stg += "var secLabel=" + secLabel;
stg += "var xLabel=[]; var i;";
stg += "for (i=0; i<=" + String(hEnd-hStart) + "; i++) {xLabel.push(" + String(tStart) + "*1000 + secLabel[i]*1000);errData[i]/=100;}";
stg += "var errLine={label:'<-Accuracy(sec)', showLine:true, lineTension:0, fill:false, borderWidth:4, borderColor:'blue', pointRadius:0, data:errData, yAxisID:'yE'};";
stg += "var outLine={label:'Current->', showLine:true, lineTension:0, fill:false, borderWidth:2, borderColor:'red', pointRadius:0, data:outData, yAxisID:'yA'};";
stg += "var opt={scales: {xAxes: [{type: 'time', time:{min:" + String(gmtNow-graphSpan) + "*000,displayFormats:{millisecond:'kk:mm',second:'kk:mm',minute:'kk:mm',hour:'M/D ha',}}}],";
stg += "yAxes: [{id:'yE',type:'linear',position:'left',ticks:{" + gYEscaleMM + "}},{id:'yA',type:'linear',position:'right',ticks:{" + gYCscaleMM + "}}]}};";
stg += "var config={type:'line', options: opt, data: {datasets: [errLine, outLine], labels: xLabel}};";
stg += "if (errChart) errChart.destroy();";
stg += "else var errChart = new Chart(ctx,config);";
stg += "function changeVal() {";
stg += "document.formGU.submit();";
stg += "}";
stg += "</script>";
String st = "Pend Ct=" + String(countPend) + " Hist=" + String(numHistory[0]) +
"<br>Error=" + csecToSecF(csecPendError) + " [" + csecToSecF(csecPendErrorMin) + ", " + csecToSecF(csecPendErrorMax) + "] sec" +
"<br>Current=" + String(adjLevel) + " [" + String(adjLevelMin) + ", " + String(adjLevelMax) + "] Ave=" + String(cadjLevelAve/100.0);
request->send(200, textHtml, msgHead + msgG + stgT + stg + st + msgEnd);
}
void updateErrorGraph(AsyncWebServerRequest *request) {
if (request->hasParam("YC")) {
String rq=request->getParam("XU")->value();
gSpanUnitIdx=(byte)atoi(rq.c_str());
rq=request->getParam("XS")->value();
graphSpan=atoi(rq.c_str())*gSpanUnit[gSpanUnitIdx];
rq=request->getParam("YE")->value();
gYEscaleIdx=atoi(rq.c_str());
gYEscale=gYEscaleNum[gYEscaleIdx];
rq=request->getParam("YC")->value();
gYCscaleIdx=atoi(rq.c_str());
gYCscale=gYCscaleNum[gYCscaleIdx];
}
graphError(request);
}
void adjControl(AsyncWebServerRequest *request) {
funcPtrWeb=adjControlExe;
funcReqWeb=request;
}
void adjControlExe(AsyncWebServerRequest *request) {
if (adjOn) {
adjOn=false;
lcdDispText(0,1, "OUT= ");
}
else {
adjOn=true;
lcdDispText(0,1, " ");
}
String st = "<h2>Control= " + String(adjOn) + "</h2>";
request->send (200, textHtml, msgHead + msgHome + st + msgEnd);
}
void dispAdj(AsyncWebServerRequest *request) {
funcPtrWeb=dispAdjExe;
funcReqWeb=request;
}
void dispAdjExe(AsyncWebServerRequest *request) {
lcdDispNum4n(9,1,adjLevel);
String st = "<h2>Current= " + String(adjLevel) + " [" + String(adjLevelMin) + ", " + String(adjLevelMax) + "]</h2>";
request->send (200, textHtml, msgHead + msgHome + st + msgEnd);
}
void confMenu(AsyncWebServerRequest *request) {
setConfigStr();
setConfigMsg();
request->send (200, textHtml, msgConf + msgEnd);
}
void setOutput(AsyncWebServerRequest *request) {
if (request->hasParam("OV")) {
String rq=request->getParam("OV")->value();
adjLevel = atoi(rq.c_str());
cadjLevel=adjLevel*100;
drvCoil(adjLevel);
dispAdj(request);
}
else request->send (200, textHtml, msgConf + "Illegal format" + msgEnd);
}
void setError(AsyncWebServerRequest *request) {
if (request->hasParam("EV")) {
funcPtrYes=setErrorExe;
funcPtrNo=dispStatus;
String rq=request->getParam("EV")->value();
float fnum=atof(rq.c_str());
secTmAdj=(int32_t)fnum;
usecTmAdj=(int32_t)((fnum-(float)secTmAdj)*1000000);
String st="<h2>Adjust Error by " + rq + "sec?</h2>";
request->send (200, textHtml, msgHead + st + msgYesNo + msgEnd);
}
else request->send (200, textHtml, msgConf + "Illegal format" + msgEnd);
}
void setErrorExe(AsyncWebServerRequest *request) {
int32_t temp=tvAtRef0.tv_usec + usecTmAdj;
int32_t carry=0;
if (temp>=1000000) {
temp -= 1000000;
carry=1;
}
else if (temp<0) {
temp += 1000000;
carry=-1;
}
tvAtRef0.tv_usec=temp;
tvAtRef0.tv_sec += carry+secTmAdj;
updateError();
csecPendErrorLast=csecPendError;
String st="<h2>Ref0 adjusted and Error set to " + csecToSecF(csecPendError) + "</h2>";
request->send (200, textHtml, msgHead + msgHome + st + msgEnd);
}
void applyConfig(AsyncWebServerRequest *request) {
if (request->hasParam("DF")) { //last parameter (date format)
pendCycle = (int32_t)atoi(request->getParam("PC")->value().c_str());
pendDur = (int32_t)atoi(request->getParam("PD")->value().c_str());
pendTuneCycle = atoi(request->getParam("PT")->value().c_str());
liftFactor = atoi(request->getParam("LF")->value().c_str());
setupMechTiming();
kP = atoi(request->getParam("KP")->value().c_str());
kI = atoi(request->getParam("KI")->value().c_str());
wifiSSID = request->getParam("WS")->value();
wifiPass = request->getParam("WP")->value();
if (request->getParam("IF")->value().charAt(0)=='1') {
staIpFixed=true;
}
else {
staIpFixed=false;
}
staIP.fromString(request->getParam("IL")->value());
staGateway.fromString(request->getParam("IG")->value());
staDNS.fromString(request->getParam("ID")->value());
staSNM.fromString(request->getParam("IS")->value());
boolean ntpByNameLast=ntpByName;
if (request->getParam("NF")->value().charAt(0)=='0') ntpByName=true;
else ntpByName=false;
ntpIPbyIP.fromString(request->getParam("NI")->value());
ntpServerName=request->getParam("NN")->value();
ntpMinInterval=(uint16_t)atoi(request->getParam("NV")->value().c_str());
ntpMaxInterval=(uint16_t)atoi(request->getParam("NX")->value().c_str());
if (ntpInterval>ntpMaxInterval) ntpInterval=ntpMaxInterval;
if (ntpInterval<ntpMinInterval) ntpInterval=ntpMinInterval;
if (ntpByNameLast != ntpByName) ntpChange();
String tzStrLast=tzStr;
tzStr=request->getParam("TZ")->value();
if (strcmp(tzStrLast.c_str(), tzStr.c_str())!=0) {
setenv("TZ", tzStr.c_str(), 1);
tzset();
}
dateFormat=(byte)atoi(request->getParam("DF")->value().c_str());
saveConfigFile();
request->send (200, textHtml, msgHead + msgHome + "<br><h2>Done</h2>" + msgEnd);
}
else {
request->send (200, textHtml, msgHead + msgHome + "<br><h2>Transmission Error</h2>" + msgEnd);
}
}
boolean saveConfigFile() {
File file = SPIFFS.open(CONFIG_FILE, FILE_WRITE);
if (!file) return false;
setConfigStr();
file.println(fileVer);
file.println(strPC);
file.println(strPD);
file.println(strPT);
file.println(strKP);
file.println(strKI);
file.println(strLF);
file.println(strWS);
file.println(strWP);
file.println(strIF);
file.println(strIL);
file.println(strIG);
file.println(strID);
file.println(strIS);
file.println(strNF);
file.println(strNI);
file.println(strNN);
file.println(strNV);
file.println(strNX);
file.println(strTZ);
file.println(strDF);
file.close();
return true;
}
void setConfigStr() {
strPC=String(pendCycle);
strPD=String(pendDur);
strPT=String(pendTuneCycle);
strKP=String(kP);
strKI=String(kI);
strLF=String(liftFactor);
strWS=wifiSSID;
strWP=wifiPass;
strIF=staIpFixed?"1":"0";
strIL=staIP.toString();
strIG=staGateway.toString();
strID=staDNS.toString();
strIS=staSNM.toString();
strNF=ntpByName?"0":"1";
strNI=ntpIPbyIP.toString();
strNN=ntpServerName;
strNV=String(ntpMinInterval);
strNX=String(ntpMaxInterval);
strTZ=tzStr;
strDF=String(dateFormat);
}
void confDefault(AsyncWebServerRequest *request) {
funcPtrYes=confDefaultExe;
funcPtrNo=dispStatus;
request->send (200, textHtml, msgHead + "<h2>Use Factory Setting?</h2><br><br>" + msgYesNo + msgEnd);
}
void confDefaultExe(AsyncWebServerRequest *request) {
loadDefaultConfig();
setConfigMsg();
request->send (200, textHtml, msgConf + "<br><h2>Default loaded but NOT applied</h2>" + msgEnd);
}
void setConfigPara() {
pendCycle=(int32_t)(atoi(strPC.c_str()));
pendDur=(int32_t)(atoi(strPD.c_str()));
pendTuneCycle=(int16_t)(atoi(strPT.c_str()));
kP=(int16_t)(atoi(strKP.c_str()));
kI=(int16_t)(atoi(strKI.c_str()));
liftFactor=(int16_t)(atoi(strLF.c_str()));
wifiSSID=strWS;
wifiPass=strWP;
staIpFixed=(strIF.charAt(0)=='1');
staIP.fromString(strIL);
staGateway.fromString(strIG);
staDNS.fromString(strID);
staSNM.fromString(strIS);
ntpByName=(strNF.charAt(0)=='0');
ntpIPbyIP.fromString(strNI);
ntpIP=ntpIPbyIP;
ntpServerName=strNN;
ntpMinInterval=(int16_t)(atoi(strNV.c_str()));
ntpMaxInterval=(int16_t)(atoi(strNX.c_str()));
tzStr=strTZ;
dateFormat=(byte)atoi(strDF.c_str());
}
void loadDefaultConfig() {
strPC=String(DEFAULT_PEND_CYCLE);
strPD=String(DEFAULT_PEND_DUR);
strPT=String(DEFAULT_TUNE_CYCLE);
strKP=String(DEFAULT_KP);
strKI=String(DEFAULT_KI);
strLF=String(DEFAULT_PEND_LF);
strWS=DEFAULT_WIFI_SSID;
strWP=DEFAULT_WIFI_PASS;
strIF=DEFAULT_STA_IP_FIX;
strIL=DEFAULT_STA_IP;
strIG=DEFAULT_STA_GW;
strID=DEFAULT_STA_DNS;
strIS=DEFAULT_SUBNET;
strNF=DEFAULT_NTP_BY_NAME?"0":"1";
strNI=DEFAULT_NTP_IP;
strNN=DEFAULT_NTP_NAME;
strNV=String(DEFAULT_NTP_MIN_INTERVAL);
strNX=String(DEFAULT_NTP_MAX_INTERVAL);
strTZ=DEFAULT_TZ_STR;
strDF=String(DEFAULT_DATE_FORMAT);
}
void setConfigMsg() {
msgConf= msgHead + "<script type='text/javascript'>\
function funcFixed() {document.getElementById('IF').style.display = 'inline';\
document.getElementById('radio1').checked = true;}\
function funcDHCP() {document.getElementById('IF').style.display = 'none';\
document.getElementById('radio2').checked = true;}\
function funcNtpF() {document.getElementById('NF').style.display = 'inline';\
document.getElementById('NN').style.display = 'none';\
document.getElementById('radio3').checked = true;}\
function funcNtpN() {document.getElementById('NF').style.display = 'none';\
document.getElementById('NN').style.display = 'inline';\
document.getElementById('radio4').checked = true;}\
window.onload = function() {" + String(strIF.charAt(0)=='1'?"funcFixed();":"funcDHCP();") +
String(strNF.charAt(0)=='1'?"funcNtpF();":"funcNtpN();") +
"document.getElementById('DF').value='" + strDF.charAt(0) + "';};</script>\
<form action='MM'><input type='submit' value='Home'></form> \
<form action='CD'><input type='submit' value='Factory'></form> \
<form action='CB'><input type='submit' value='Reboot'></form> \
<form id='form1' action='CA'><button type=submit' form='form1'>Apply</button><br>\
<hr width='800px'>\
Pendulum:<input id='PC' type='number' min='1' name='PC' value='" + strPC + "'>cycles=\
<input type='number' min='1' name='PD' value='" + strPD + "'>sec\
<br>Pend Cycle between Tune:<input type='number' min='1' name='PT' value='" + strPT + "'>\
<br>KP:<input type='number' min='0' name='KP' value='" + strKP + "'>&nbsp;\
KI:<input type='number' min='0' name='KI' value='" + strKI + "'>\
Lift/Swing:<input type='number' min='1' max='720' name='LF' value='" + strLF + "'>\
<br><hr width='800px'>\
<span>WiFi SSID:</span><input type='text' name='WS' value='" + strWS + "'><br>\
<span>WiFi Pass:</span><input type='text' name='WP' value='" + strWP + "'><br>\
<hr width='800px'>\
<input type='radio' id='radio1' name='IF' value='1' onclick='funcFixed()' />\
<label for='radio1'><span style='width:250px;text-align:left'>Fixed IP</span></label>\
<input type='radio' id='radio2' name='IF' value='0' onclick='funcDHCP()' />\
<label for='radio2'><span style='width:300px;text-align:left'>DHCP</span></label>\
<span id='IF'><br>\
<span>Local IP:</span><input type='text' name='IL' value='" + strIL + "'><br>\
<span>Gateway IP:</span><input type='text' name='IG' value='" + strIG + "'><br>\
<span>DNS IP:</span><input type='text' name='ID' value='" + strID + "'><br>\
<span>Subnet Mask:</span><input type='text' name='IS' value='" + strIS + "'></span><br>\
<hr width='800px'>\
<input type='radio' id='radio3' name='NF' value='1' onclick='funcNtpF()' />\
<label for='radio3'><span style='width:250px;text-align:left'>NTP IP</span></label>\
<input type='radio' id='radio4' name='NF' value='0' onclick='funcNtpN()' />\
<label for='radio4'><span style='width:300px;text-align:left'>NTP Name</span></label>\
<span id='NF'><br><span>NTP IP:</span><input type='text' name='NI' value='" + strNI + "'></span>\
<span id='NN'><br><span>NTP Name:</span><input type='text' name='NN' value='" +strNN + "'></span><br>\
Interval Min:<input type='number' min='1' max='1440' name='NV' value='" + strNV + "'> \
Max:<input type='number' min='1' max='1440' step='1' name='NX' value='" + strNX + "'>min<br>\
<hr width='800px'>\
<span>TZ/DST:</span><input type='text' list='tzList' name='TZ' value='" + strTZ + "' placeholder='Select or type in'><br>\
<datalist id='tzList'>\
<option value='" + TZ_STR0 + "'>\
<option value='" + TZ_STR1 + "'>\
<option value='" + TZ_STR2 + "'>\
<option value='" + TZ_STR3 + "'>\
</datalist>\
<span>Date Format:</span><select id='DF' name='DF' form='form1' style='width:500px;font-size:36pt;margin-right:50px'>\
<option value='0'>Select format</option>\
<option value='1'>" + dateStr[1] + "</option>\
<option value='2'>" + dateStr[2] + "</option>\
<option value='3'>" + dateStr[3] + "</option></select><br></form>"; //when changed, make sure to check that bottom alignment
}
boolean loadConfigFile() {
File file = SPIFFS.open(CONFIG_FILE, FILE_READ);
if (!file) return false;
if (file.available()) {
strVer=file.readStringUntil('\r');file.read();
if (strVer.compareTo(fileVer)!=0) {
file.close();
return false;
}
strPC=file.readStringUntil('\r');file.read();
strPD=file.readStringUntil('\r');file.read();
strPT=file.readStringUntil('\r');file.read();
strKP=file.readStringUntil('\r');file.read();
strKI=file.readStringUntil('\r');file.read();
strLF=file.readStringUntil('\r');file.read();
strWS=file.readStringUntil('\r');file.read();
strWP=file.readStringUntil('\r');file.read();
strIF=file.readStringUntil('\r');file.read();
strIL=file.readStringUntil('\r');file.read();
strIG=file.readStringUntil('\r');file.read();
strID=file.readStringUntil('\r');file.read();
strIS=file.readStringUntil('\r');file.read();
strNF=file.readStringUntil('\r');file.read();
strNI=file.readStringUntil('\r');file.read();
strNN=file.readStringUntil('\r');file.read();
strNV=file.readStringUntil('\r');file.read();
strNX=file.readStringUntil('\r');file.read();
strTZ=file.readStringUntil('\r');file.read();
strDF=file.readStringUntil('\r');
file.close();
return true;
}
}
void confLoad(AsyncWebServerRequest *request) {
loadConfigFile();
setConfigMsg();
request->send (200, textHtml, msgConf + msgEnd);
}
void confReboot(AsyncWebServerRequest *request) {
funcPtrYes=espReset;
funcPtrNo=confMenu;
request->send (200, textHtml, msgHead + "<h2>CPU Reset?</h2><br><br>" + msgYesNo + msgEnd);
}
void espReset(AsyncWebServerRequest *request) {
funcPtrYes=dispStatus;
request->send (200, textHtml, msgHead + "<h2>CPU Resetting...</h2>" + msgEnd);
ESP.restart();
}
void ansYes(AsyncWebServerRequest *request) {
if (funcPtrYes) funcPtrYes(request);
else dispStatus(request);
}
void ansNo(AsyncWebServerRequest *request) {
if (funcPtrNo) funcPtrNo(request);
else dispStatus(request);
}
void sensAdjOn(AsyncWebServerRequest *request) {
sensAdjMode=true;
oled.clear();
funcPtrYes=sensAdjOff;
funcPtrNo=dispStatus;
request->send (200, textHtml, msgHead + "<h2>End Sensor Adj mode?</h2><br><br>" + msgYesNo + msgEnd);
}
void sensAdjOff(AsyncWebServerRequest *request) {
sensAdjMode=false;
ledOff();
dispStatus(request);
}
void setupServer() {
server.on("/", dispStatus);
server.on("/TC", adjControl);
server.on("/SO", setOutput);
server.on("/H0", hand0Sec);
server.on("/SE", setError);
server.on("/EZ", zeroError);
server.on("/MR", resetMinMax);
server.on("/ST", dispStatus);
server.on("/GU", updateErrorGraph);
server.on("/GR", graphError);
server.on("/CF", confMenu);
server.on("/CA", applyConfig);
server.on("/CD", confDefault);
server.on("/MM", dispStatus);
server.on("/CB", confReboot);
server.on("/SA", sensAdjOn);
server.on("/YS", ansYes);
server.on("/NO", ansNo);
server.onNotFound(handleNotFound);
server.begin();
}
void lcdDispText(int16_t col, int16_t row, String s) {
lcdDispText2(col, row, s, 128);
}
void lcdDispText2(int16_t col, int16_t row, String s, int16_t width) {
oled.setColor(BLACK);
oled.fillRect(col*CHAR_W, row*CHAR_H, width, 18);
oled.setColor(WHITE);
oled.drawString(col*CHAR_W, row*CHAR_H, s);
oled.display();
}
void lcdDispNumF(int16_t col, int16_t row, int32_t n) {
char pNum[10]={0};
if (n>9999999) snprintf(pNum, 10, "%s", "+> ");
else if (n<-999999) snprintf(pNum, 10, "%s", "-< ");
else snprintf(pNum, 10, "%08.2f", ((float)n)/100.0);
oled.setColor(BLACK);
oled.fillRect(col*CHAR_W, row*CHAR_H, 72, 16);
oled.setColor(WHITE);
oled.drawString(col*CHAR_W, row*CHAR_H, pNum);
oled.display();
}
void lcdDispNum3n(int16_t col, int16_t row, int32_t n) {
char pNum[5]={0};
if (abs32(n)<=999) snprintf(pNum, 5, "%3d", n);
else snprintf(pNum, 5, "%s", "***");
oled.setColor(BLACK);
oled.fillRect(col*CHAR_W, row*CHAR_H, 30, 16);
oled.setColor(WHITE);
oled.drawString(col*CHAR_W, row*CHAR_H, pNum);
oled.display();
}
void lcdDispNum4n(int16_t col, int16_t row, int32_t n) {
char pNum[6]={0};
if (abs32(n)<=9999) snprintf(pNum, 6, "%4d", n);
else snprintf(pNum, 6, "%s", "***");
oled.setColor(BLACK);
oled.fillRect(col*CHAR_W, row*CHAR_H, 44, 16);
oled.setColor(WHITE);
oled.drawString(col*CHAR_W, row*CHAR_H, pNum);
oled.display();
}
void lcdDispTime(int16_t col, int16_t row, byte mode) { //mode1=data and time, mode2=time only
struct tm tt;
localtime_r(&gmtAtSec, &tt);
tzDst=tt.tm_isdst;
char buf[20]={0};
char tim[20]={0};
if (mode==1) strftime(buf, 20, dateFmtMD[dateFormat].c_str(), &tt);
snprintf(tim, 20, "%s %02d:%02d:%02d", buf, tt.tm_hour, tt.tm_min, tt.tm_sec);
oled.setColor(BLACK);
oled.fillRect(col*CHAR_W, row*CHAR_H, 128, 16);
oled.setColor(WHITE);
oled.drawString(col*CHAR_W, row*CHAR_H, tim);
if (tzDst==0 && tzDstObs) oled.drawCircle(123, 9, 4);
else if (tzDst>0) oled.fillCircle(123, 9, 4);
oled.display();
}
void lcdDispGraph() {
#if defined(HMC5883)
if (sensAdjMode) return;
#endif
if (digitalRead(BTN_PIN)==LOW) return;
int32_t eMax=1;
int16_t aMax=1, diff;
byte idxA, idxE;
int32_t hStart=numHistory[0]-30; //SCREEN_W; //use the last 30 points for scaling
if (hStart<0) hStart=0;
for (int32_t i=hStart; i<=numHistory[0]; i++) {
if (abs32(errorHistory[0][i%N_HISTORY])>eMax) eMax=abs32(errorHistory[0][i%N_HISTORY]);
diff=abs16(adjHistory[0][i%N_HISTORY]-adjLevel);
if (diff>aMax) aMax=diff;
}
for (idxE=0; idxE<numgE; idxE++) {
if (gscaleE[idxE]>=eMax) break;
}
if (idxE>=numgE) idxE=numgE-1;
for (idxA=0; idxA<numgA; idxA++) {
if (gscaleA[idxA]>=aMax) break;
}
if (idxA>=numgA) idxA=numgA-1;
clearGraph();
lcdSetColor(WHITE);
lcdDrawLine(0, GYCENTER, GXORIGIN, GYCENTER);
lcdDrawLine(GXORIGIN, GYCENTER-16, GXORIGIN, GYCENTER+16);
lcdDrawLine(GXORIGIN, GYCENTER-10, GXORIGIN+2, GYCENTER-10);
lcdDrawLine(GXORIGIN, GYCENTER+10, GXORIGIN+2, GYCENTER+10);
oled.setFont(ArialMT_Plain_10);
String scaleMark;
if ((lcdGmode==0) && (gmtAtSec%lcdGrAltSec<(lcdGrAltSec/2)) || (lcdGmode==1)) {
if (gscaleE[idxE]>=100) scaleMark=String(gscaleE[idxE]/100)+"s";
else scaleMark=String(gscaleE[idxE]*10)+"ms";
lcdDrawString(GXORIGIN+4, GYCENTER-16, "+"+scaleMark);
lcdDrawString(GXORIGIN+4, GYCENTER+4, "-"+scaleMark);
}
else if ((lcdGmode==0) && (gmtAtSec%lcdGrAltSec>=(lcdGrAltSec/2)) || (lcdGmode==2)) {
lcdDrawString(GXORIGIN+4, GYCENTER-16, String(gscaleA[idxA]+(adjLevel/10)*10));
lcdDrawString(GXORIGIN+4, GYCENTER+4, String(-gscaleA[idxA]+(adjLevel/10)*10));
}
oled.setFont(OLEDFONT);
time_t endSec=tHistory[0][numHistory[0]%N_HISTORY];
int16_t dotPerHour=3600/tuneInterval;
for (int i=1; i<=GRAPH_W; i++) {
if (i%4==0) {
lcdSetPixel(GRAPH_W-i, GTOP);
lcdSetPixel(GRAPH_W-i, GBOTTOM);
}
if ((i-1)%dotPerHour==0) { //every 1 hour back from now
for (int y=GTOP; y<=GBOTTOM; y++) {
if (y%4==0) lcdSetPixel(GRAPH_W-i, y);
}
}
}
lcdSetColor(WHITE);
int32_t yE;
int16_t yA;
hStart=numHistory[0]-GRAPH_W;
int16_t offset=0;
if (hStart<0) {
hStart=0;
offset=GRAPH_W-numHistory[0];
}
if ((lcdGmode==0) && (gmtAtSec%lcdGrAltSec<(lcdGrAltSec/2)) || (lcdGmode==1)) {
for (int32_t i=hStart; i<=numHistory[0]; i++) {
yE=errorHistory[0][i%N_HISTORY]*10/gscaleE[idxE];
if (abs32(yE)<=GBOTTOM-GYCENTER) lcdSetPixel(GXORIGIN+i-hStart+offset, GYCENTER-yE);
if (i==numHistory[0]) lcdDrawCircle(GXORIGIN+i-hStart+offset, constrain(GYCENTER-csecPendError*10/gscaleE[idxE], GTOP, GBOTTOM), 2);
}
for (int x=GXORIGIN; x<GXORIGIN+GRAPH_W; x++) {
if (x%2==0) lcdSetPixel(x, GYCENTER);
}
}
else if ((lcdGmode==0) && (gmtAtSec%lcdGrAltSec>=(lcdGrAltSec/2)) || (lcdGmode==2)) {
for (int32_t i=hStart; i<=numHistory[0]; i++) {
yA=(adjHistory[0][i%N_HISTORY]-adjLevel)*10/gscaleA[idxA];
if (abs16(yA)<=GBOTTOM-GYCENTER) lcdSetPixel(GXORIGIN+i-hStart+offset, GYCENTER-yA);
}
if (adjLevel>=0) lcdFillRect(0, GYCENTER-16*adjLevel/ADJ_MAX, GXORIGIN, 16*adjLevel/ADJ_MAX);
else lcdFillRect(0, GYCENTER, GXORIGIN, -16*adjLevel/ADJ_MAX);
int16_t yZeroPos=GYCENTER+10*adjLevel/gscaleA[idxA];
if (yZeroPos>=GTOP && yZeroPos<=GBOTTOM) {
for (int x=GXORIGIN; x<GXORIGIN+GRAPH_W; x++) {
if (x%2==0) lcdSetPixel(x, yZeroPos);
}
}
}
}
void clearGraph() {
oled.setColor(BLACK);
oled.fillRect(0, GTOP-2, 128, GBOTTOM-GTOP+3);
}
void setupOled() {
oled.init();
oled.setFont(ArialMT_Plain_16);
}
void lcdDrawLine(int x0, int y0, int x1, int y1) {
oled.drawLine(x0, y0, x1, y1);
}
void lcdSetColor(OLEDDISPLAY_COLOR color) {
oled.setColor(color);
}
void lcdDrawString(int x0, int y0, String s) {
oled.drawString(x0, y0, s);
}
void lcdSetPixel(int x0, int y0) {
oled.setPixel(x0, y0);
}
void lcdDrawCircle(int x0, int y0, int r) {
oled.drawCircle(x0, y0, r);
}
void lcdFillRect(int x0, int y0, int x1, int y1) {
oled.fillRect(x0, y0, x1, y1);
}
void setupOta() {
ArduinoOTA.begin();
ArduinoOTA.onStart([]() {
detachInterrupt(digitalPinToInterrupt(SENS_PIN));
oled.clear();
oled.setFont(ArialMT_Plain_10);
oled.setTextAlignment(TEXT_ALIGN_CENTER_BOTH);
oled.drawString(oled.getWidth()/2, oled.getHeight()/2 - 10, "OTA Update");
oled.display();
});
ArduinoOTA.onProgress([](unsigned int progress, unsigned int total) {
oled.drawProgressBar(4, 32, 120, 8, progress / (total / 100) );
oled.display();
});
ArduinoOTA.onEnd([]() {
oled.clear();
oled.setFont(ArialMT_Plain_10);
oled.setTextAlignment(TEXT_ALIGN_CENTER_BOTH);
oled.drawString(oled.getWidth()/2, oled.getHeight()/2, "Restart");
oled.display();
});
}
void setupFile() {
SPIFFS.begin();
if (!SPIFFS.exists(CONFIG_FILE)) {
SPIFFS.format();
}
}
#ifdef HMC5883
void magTrigH() {
if (pendDir==0 && (millis()-milliSensRelease)>minSensOffDuration) {
pendDir=1;
sensTrig=true;
milliSensTrig=millis();
if (refSet) {
countPend++;
csecPend=(int64_t)countPend * (int64_t)pendDur * 100 / (int64_t)pendCycle;
}
}
}
void magTrigL() {
if (pendDir==1 && (millis()-milliSensTrig)>minSensOnDuration) {
pendDir=0;
sensRelease=true;
milliSensRelease=millis();
}
}
void setupHMC5883() {
Wire.beginTransmission(MAG_ADDR);
Wire.write(0x02); // Register
Wire.write(0x00); // Continuous Measure
Wire.endTransmission();
}
void getHMC5883() {
Wire.beginTransmission(MAG_ADDR);
Wire.write(0x03); //start with register 3.
Wire.endTransmission();
Wire.requestFrom(MAG_ADDR, 6);
if(Wire.available()>=6) {
magX = Wire.read()<<8; //MSB x
magX |= Wire.read(); //LSB x
magZ = Wire.read()<<8; //MSB z
magZ |= Wire.read(); //LSB z
magY = Wire.read()<<8; //MSB y
magY |= Wire.read(); //LSB y
}
}
byte readHMC5883(byte reg) {
Wire.beginTransmission(MAG_ADDR);
Wire.write(reg);
Wire.endTransmission();
Wire.requestFrom(MAG_ADDR, 1);
return Wire.read();
}
#endif
void setupMechTiming() {
pendPeriod=(float)pendDur * 1000.0 / (float)pendCycle; //msec/cycle
pendPeriodMs=(uint32_t)pendPeriod;
if (pendPeriodMs>5000) lcdGrAltSec=pendPeriodMs/500;
else lcdGrAltSec=10;
float factor;
#ifdef MIN_SENS_DUR_OFF
minSensOffDuration = MIN_SENS_DUR_OFF;
#else
if (pendPeriod<600) factor=0.3; //balance wheele type
else if (pendPeriod>4000) factor=0.75; //torsion pendulum type
else factor=0.5; //gravity pendulum type
minSensOffDuration = (int32_t)(pendPeriod * factor);
#endif
#ifdef MIN_SENS_DUR_ON
minSensOnDuration = MIN_SENS_DUR_ON;
#else
if (pendPeriod<600) factor=0.3;
else factor=0.01;
minSensOnDuration = (int32_t)(pendPeriod * factor);
#endif
pendWindow = (int32_t)(pendPeriod * 1.3 + 1000.0);
tuneIntervalMs = (int32_t)pendPeriod * (int32_t)pendTuneCycle; //in msec
tuneInterval=tuneIntervalMs / 1000; //in sec
if (liftFactor>=LIFT_SWING) { //torsion pend
float factP0;
if (liftFactor<=270) factP0=0.0; //full drive
else factP0=(float)(liftFactor-270)/600.0; //partial drive 360deg=0.4-0.7
partial0End=(int32_t)(pendPeriod*(0.55+factP0));
partial0Start=(int32_t)(pendPeriod*(0.55-factP0));
}
}
void ledOn() {
digitalWrite(LED_PIN, LED_ON);
}
void ledOff() {
digitalWrite(LED_PIN, LED_OFF);
}
view raw cTune323p.ino hosted with ❤ by GitHub