diff --git a/RX_FSK/RX_FSK.ino b/RX_FSK/RX_FSK.ino index fda1aba..197b05f 100644 --- a/RX_FSK/RX_FSK.ino +++ b/RX_FSK/RX_FSK.ino @@ -320,7 +320,7 @@ const char *handleQRGPost(AsyncWebServerRequest *request) { const char *fstr = fstring.c_str(); const char *tstr = tstring.c_str(); const char *sstr = sstring.c_str(); - if(*tstr=='6' || *tstr=='9') tstr="D"; + if (*tstr == '6' || *tstr == '9') tstr = "D"; Serial.printf("Processing a=%s, f=%s, t=%s, site=%s\n", active ? "YES" : "NO", fstr, tstr, sstr); char typech = tstr[0]; file.printf("%3.3f %c %c %s\n", atof(fstr), typech, active ? '+' : '-', sstr); @@ -1902,7 +1902,7 @@ void setup() Serial.println("AXP192 Begin FAIL"); } axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); - if(sonde.config.type == TYPE_M5_CORE2) { + if (sonde.config.type == TYPE_M5_CORE2) { // Display backlight on M5 Core2 axp.setPowerOutPut(AXP192_DCDC3, AXP202_ON); axp.setDCDC3Voltage(3300); @@ -1931,7 +1931,9 @@ void setup() delay(500); } } - if (sonde.config.batt_adc>=0) { pinMode(sonde.config.batt_adc, INPUT); } + if (sonde.config.batt_adc >= 0) { + pinMode(sonde.config.batt_adc, INPUT); + } if (sonde.config.power_pout >= 0) { // for a heltec v2, pull GPIO21 low for display power pinMode(sonde.config.power_pout & 127, OUTPUT); digitalWrite(sonde.config.power_pout & 127, sonde.config.power_pout & 128 ? 1 : 0); @@ -2027,11 +2029,11 @@ void setup() #if 1 - if(sonde.config.type == TYPE_M5_CORE2) { - // Core2 uses Pin 38 for MISO - SPI.begin(18, 38, 23, -1); + if (sonde.config.type == TYPE_M5_CORE2) { + // Core2 uses Pin 38 for MISO + SPI.begin(18, 38, 23, -1); } else { - SPI.begin(); + SPI.begin(); } //Set most significant bit first SPI.setBitOrder(MSBFIRST); @@ -2040,23 +2042,23 @@ void setup() //Set data mode SPI.setDataMode(SPI_MODE0); -sx1278.setup(globalLock); + sx1278.setup(globalLock); -int i=0; -while(++i<3) { - delay(500); - // == check the radio chip by setting default frequency =========== // - sx1278.ON(); - if (sx1278.setFrequency(402700000) == 0) { - Serial.println(F("Setting freq: SUCCESS ")); - } else { - Serial.println(F("Setting freq: ERROR ")); + int i = 0; + while (++i < 3) { + delay(500); + // == check the radio chip by setting default frequency =========== // + sx1278.ON(); + if (sx1278.setFrequency(402700000) == 0) { + Serial.println(F("Setting freq: SUCCESS ")); + } else { + Serial.println(F("Setting freq: ERROR ")); + } + float f = sx1278.getFrequency(); + Serial.print("Frequency set to "); + Serial.println(f); + // == check the radio chip by setting default frequency =========== // } - float f = sx1278.getFrequency(); - Serial.print("Frequency set to "); - Serial.println(f); - // == check the radio chip by setting default frequency =========== // -} #endif //sx1278.setLNAGain(-48); @@ -3223,7 +3225,9 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub * struct tm ts; uint8_t realtype = s->type; // config setting M10 and M20 will both decode both types, so use the real type that was decoded - if(TYPE_IS_METEO(realtype)) { realtype = s->subtype==1 ? STYPE_M10 : STYPE_M20; } + if (TYPE_IS_METEO(realtype)) { + realtype = s->subtype == 1 ? STYPE_M10 : STYPE_M20; + } // For DFM, s->time is data from subframe DAT8 (gps date/hh/mm), and sec is from DAT1 (gps sec/usec) // For all others, sec should always be 0 and time the exact time in seconds @@ -3237,7 +3241,7 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub * while (client->available() > 0) { // data is available from remote server, process it... - int cnt = client->readBytesUntil('\n', rs_msg, MSG_SIZE-1); + int cnt = client->readBytesUntil('\n', rs_msg, MSG_SIZE - 1); rs_msg[cnt] = 0; Serial.println(rs_msg); // If something that looks like a valid HTTP response is received, we are ready to send the next data item diff --git a/RX_FSK/data/index.html b/RX_FSK/data/index.html index e5f75ad..16c44cc 100755 --- a/RX_FSK/data/index.html +++ b/RX_FSK/data/index.html @@ -53,7 +53,7 @@ Copyright © 2019-2021 by Hansi Reiser, DL9RDZ
(version %VERSION_ID%)

- Check for update (requires TTGO internet connection via WiFi)

+ Check for update (requires TTGO internet connection via WiFi)

with contributions by Vigor and Xavier (M20 support), Luke Prior and OH3BSG (SondeHub support), diff --git a/RX_FSK/data/upd.html b/RX_FSK/data/upd.html new file mode 100644 index 0000000..8f4bf65 --- /dev/null +++ b/RX_FSK/data/upd.html @@ -0,0 +1,36 @@ + + + + + + +

Currently installed: devel20210908-B14

+

+Available master: (...checking...) + +
+Available devel: (...checking...) + +

+
+
+

Note: If suffix is the same, update should work fully. If the number is different, update contains changes in the file system. A full re-flash is required to get all new features, but the update should not break anything. If the letter is different, a full re-flash is mandatory, update will not work

+ + + diff --git a/RX_FSK/src/DFM.cpp b/RX_FSK/src/DFM.cpp index 3401800..12fcc46 100644 --- a/RX_FSK/src/DFM.cpp +++ b/RX_FSK/src/DFM.cpp @@ -546,12 +546,6 @@ int DFM::decodeFrameDFM(uint8_t *data) { deinterleave(data, 7, hamming_conf); deinterleave(data+7, 13, hamming_dat1); deinterleave(data+20, 13, hamming_dat2); -#if 0 - Serial.print("RAWCFG:"); - for(int i=0; i<7*8; i++) { - Serial.print(hamming_conf[i]?"1":"0"); - } -#endif int ret0 = hamming(hamming_conf, 7, block_conf); int ret1 = hamming(hamming_dat1, 13, block_dat1); @@ -575,22 +569,6 @@ int DFM::decodeFrameDFM(uint8_t *data) { // moved to a single function in Sonde(). This function can be used for additional // processing here, that takes too long for doing in the RX task loop int DFM::waitRXcomplete() { -#if 0 - int res=0; - uint32_t t0 = millis(); - while( rxtask.receiveResult < 0 && millis()-t0 < 2000) { delay(50); } - - if( rxtask.receiveResult<0 || rxtask.receiveResult==RX_TIMEOUT) { - res = RX_TIMEOUT; - } else if ( rxtask.receiveResult ==0) { - res = RX_OK; - } else { - res = RX_ERROR; - } - rxtask.receiveResult = -1; - Serial.printf("waitRXcomplete returning %d\n", res); - return res; -#endif return 0; } diff --git a/RX_FSK/src/Display.cpp b/RX_FSK/src/Display.cpp index 278866b..0ab5b4c 100644 --- a/RX_FSK/src/Display.cpp +++ b/RX_FSK/src/Display.cpp @@ -551,20 +551,6 @@ void ILI9225Display::drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile } tft->endWrite(); SPI_MUTEX_UNLOCK(); -#if 0 - int i,j; - tft->startWrite(); - for(int i=0; idrawPixel(8*x+i, 8*y+j, (v&0x01) ? COLOR_GREEN:COLOR_BLUE); - v >>= 1; - } - } - tft->endWrite(); - //tft->drawBitmap(x*8, y*8, tile_ptr, cnt*8, 8, COLOR_RED, COLOR_BLUE); - //???u8x8->drawTile(x, y, cnt, tile_ptr); -#endif } void ILI9225Display::drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, boolean fill) { @@ -1081,11 +1067,6 @@ void Display::initFromFile(int index) { what++; newlayouts[idx].de[what].func = NULL; } else { -#if 0 - for(int i=0; i<12; i++) { - Serial.printf("action %d: %d\n", i, (int)newlayouts[idx].actions[i]); - } -#endif what=-1; } break; diff --git a/RX_FSK/src/MP3H.cpp b/RX_FSK/src/MP3H.cpp index 4ffb858..1c6e0aa 100644 --- a/RX_FSK/src/MP3H.cpp +++ b/RX_FSK/src/MP3H.cpp @@ -62,46 +62,6 @@ int MP3H::setup(float frequency) return 1; } -#if 0 -/// TODO: Maybe do this conditionally? -- maybe skip if afc if agcbw set to 0 or -1? -//// Step 1: Tentative AFC mode - sx1278.clearIRQFlags(); - // preamble detector + AFC + AGC on - // wait for preamble interrupt within 2sec - sx1278.setBitrate(4800); - // DetectorOn=1, Preamble detector size 01, preamble tol 0x0A (10) - sx1278.setPreambleDetect(0x80 | 0x20 | 0x0A); - // Manual start RX, Enable Auto-AFC, Auto-AGC, RX Trigger (AGC+AFC)by preamble - sx1278.setRxConf(0x20 | 0x10 | 0x08 | 0x06); - // Packet config 1: fixed len, no mancecer, no crc, no address filter - // Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0) - if(sx1278.setPacketConfig(0x08, 0x40)!=0) { - MP3H_DBG(Serial.println("Setting Packet config FAILED")); - return 1; - } - // enable RX - sx1278.setPayloadLength(0); - sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE); - unsigned long t0 = millis(); - MP3H_DBG(Serial.printf("MP3H::setup() AFC preamble search start at %ld\n",t0)); - while( millis() - t0 < 1000 ) { - uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS1); - if(value & 2) { - int32_t afc = sx1278.getAFC(); - int16_t rssi = sx1278.getRSSI(); - Serial.printf("MP3H::setup: preamble: AFC is %d, RSSI is %.1f\n", afc, rssi/2.0); - sonde.sondeList[rxtask.currentSonde].rssi = rssi; - sonde.sondeList[rxtask.currentSonde].afc = afc; - break; - } - yield(); - } - if( millis() - t0 >= 1000) { - Serial.println("Preamble scan for AFC: TIMEOUT\n"); - return 1; // no preamble, so we may fail fast.... - } -#endif - //// Step 2: Real reception // FSK standby mode, seems like otherweise baudrate cannot be changed? sx1278.setFSK(); diff --git a/RX_FSK/src/RS41.cpp b/RX_FSK/src/RS41.cpp index 84fc75e..ac7c053 100644 --- a/RX_FSK/src/RS41.cpp +++ b/RX_FSK/src/RS41.cpp @@ -17,18 +17,6 @@ static byte data[800]; static int dpos = 0; -#if 0 -// subframe is never used? -static byte subframe[51*16]; // 816 subframe bytes -// this is moved to sondeInfo->extra -static bool subframeReceived[51] = { false }; // do we have data for row -static bool subframeComplete = false; // is the subframe complete -// this is needed only locally, use a local variable on stack for that -static bool validExternalTemperature = false; // have received all the calibration frames for the external temperature -static bool validHumidity = false; // have received all the calibration frames for the humidity -static bool validRAExternalTemperature = false; // have received all the calibration frames for the external temperature -static bool validRAHumidity = false; // have received all the calibration frames for the humidity -#endif // whole 51 row frame as C structure // taken from https://github.com/einergehtnochrein/ra-firmware @@ -715,13 +703,6 @@ int RS41::decode41(byte *data, int maxlen) sonde.si()->countKT = cntdown; sonde.si()->crefKT = fnr; } -#if 0 - // process this subframe - int subframeOffset = 24; // 24 = 0x18, start of subframe data - byte receivedBytes[16]; - memcpy( receivedBytes, data+p+subframeOffset, 16); - ProcessSubframe( receivedBytes, calnr ); -#endif ProcessSubframe( data+p+24, calnr ); } @@ -754,9 +735,11 @@ int RS41::decode41(byte *data, int maxlen) uint32_t tempHumiMain = getint24(data, 560, p+18); uint32_t tempHumiRef1 = getint24(data, 560, p+21); uint32_t tempHumiRef2 = getint24(data, 560, p+24); + #if 0 uint32_t pressureMain = getint24(data, 560, p+27); uint32_t pressureRef1 = getint24(data, 560, p+30); uint32_t pressureRef2 = getint24(data, 560, p+33); + #endif #if 0 Serial.printf( "External temp: tempMeasMain = %ld, tempMeasRef1 = %ld, tempMeasRef2 = %ld\n", tempMeasMain, tempMeasRef1, tempMeasRef2 ); Serial.printf( "Rel Humidity: humidityMain = %ld, humidityRef1 = %ld, humidityRef2 = %ld\n", humidityMain, humidityRef1, humidityRef2 ); @@ -856,22 +839,6 @@ int RS41::receive() { int RS41::waitRXcomplete() { // Currently not used. can be used for additinoal post-processing // (required for RS92 to avoid FIFO overrun in rx task) -#if 0 - int res; - uint32_t t0 = millis(); - while(rxtask.receiveResult<0 && millis()-t0 < 3000) { delay(50); } - - if(rxtask.receiveResult<0 || rxtask.receiveResult==RX_TIMEOUT) { - res = RX_TIMEOUT; - } else if (rxtask.receiveResult==0) { - res = RX_OK; - } else { - res = RX_ERROR; - } - rxtask.receiveResult = -1; - Serial.printf("waitRXcomplete returning %d\n", res); - return res; -#endif return 0; } diff --git a/RX_FSK/src/RS92.cpp b/RX_FSK/src/RS92.cpp index ebb4034..fbef505 100644 --- a/RX_FSK/src/RS92.cpp +++ b/RX_FSK/src/RS92.cpp @@ -17,7 +17,6 @@ #define RS92_DBG(x) #endif -//static uint16_t CRCTAB[256]; uint16_t *CRCTAB = NULL; #define X2C_DIVR(a, b) ((b) != 0.0f ? (a)/(b) : (a)) @@ -39,27 +38,6 @@ static uint32_t X2C_LSH(uint32_t a, int32_t length, int32_t n) return (a >> -n) & m; } -#if 0 -static double atang2(double x, double y) -{ - double w; - if (fabs(x)>fabs(y)) { - w = (double)atan((float)(X2C_DIVL(y,x))); - if (x<0.0) { - if (y>0.0) w = 3.1415926535898+w; - else w = w-3.1415926535898; - } - } - else if (y!=0.0) { - w = (double)(1.5707963267949f-atan((float)(X2C_DIVL(x, - y)))); - if (y<0.0) w = w-3.1415926535898; - } - else w = 0.0; - return w; -} /* end atang2() */ -#endif - static void Gencrctab(void) { uint16_t j; @@ -196,19 +174,6 @@ int RS92::setup(float frequency) return res; } -#if 0 -int RS92::setFrequency(float frequency) { - Serial.print("RS92: setting RX frequency to "); - Serial.println(frequency); - int res = sx1278.setFrequency(frequency); - // enable RX - sx1278.setPayloadLength(0); // infinite for now... - - sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE); - return res; -} -#endif - uint32_t RS92::bits2val(const uint8_t *bits, int len) { uint32_t val = 0; for (int j = 0; j < len; j++) { @@ -448,34 +413,6 @@ void RS92::printRaw(uint8_t *data, int len) Serial.println(); } -#if 0 -// I guess this is old copy&paste stuff from RS41?? -int RS92::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len) -{ - int i; - for(i=0; i>4]; -} - - -static uint8_t scramble[64] = {150U,131U,62U,81U,177U,73U,8U,152U,50U,5U,89U, - 14U,249U,68U,198U,38U,33U,96U,194U,234U,121U,93U,109U,161U, - 84U,105U,71U,12U,220U,232U,92U,241U,247U,118U,130U,127U,7U, - 153U,162U,44U,147U,124U,48U,99U,245U,16U,46U,97U,208U,188U, - 180U,182U,6U,170U,244U,35U,120U,110U,59U,174U,191U,123U,76U, - 193U}; -#endif - void RS92::stobyte92(uint8_t b) { @@ -631,97 +568,9 @@ int RS92::waitRXcomplete() { si->time = (gpx.gpssec/1000) + 86382 + gpx.week*604800 + 315878400UL; si->validTime = true; -#if 0 - int res=0; - uint32_t t0 = millis(); - while( rxtask.receiveResult == 0xFFFF && millis()-t0 < 2000) { delay(20); } - - if( rxtask.receiveResult<0 || rxtask.receiveResult==RX_TIMEOUT) { - res = RX_TIMEOUT; - } else if ( rxtask.receiveResult==0) { - res = RX_OK; - } else { - res = RX_ERROR; - } - rxtask.receiveResult = 0xFFFF; - Serial.printf("RS92::waitRXcomplete returning %d (%s)\n", res, RXstr[res]); - return res; -#endif return 0; } -#if 0 -int oldwaitRXcomplete() { - Serial.println("RS92: receive frame...\n"); - sx1278receiveData = true; - delay(6000); // done in other task.... - //sx1278receiveData = false; -#if 0 - //sx1278.setPayloadLength(518-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header) - //sx1278.setPayloadLength(0); // infinite for now... - -////// test code for continuous reception - // sx1278.receive(); /// active FSK RX mode -- already done above... - uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2); - unsigned long previous = millis(); - - byte ready=0; - uint32_t wait = 8000; - // while not yet done or FIFO not yet empty - // bit 6: FIFO Empty - // bit 2 payload ready - int by=0; - while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) ) - { - if( bitRead(value, 7) ) { Serial.println("FIFO full"); } - if( bitRead(value, 4) ) { Serial.println("FIFO overflow"); } - if( bitRead(value,2)==1 ) ready=1; - if( bitRead(value, 6) == 0 ) { // FIFO not empty - byte data = sx1278.readRegister(REG_FIFO); - process8N1data(data); - by++; -#if 0 - if(di==1) { - int rssi=getRSSI(); - int fei=getFEI(); - int afc=getAFC(); - Serial.print("Test: RSSI="); Serial.println(rssi); - Serial.print("Test: FEI="); Serial.println(fei); - Serial.print("Test: AFC="); Serial.println(afc); - sonde.si()->rssi = rssi; - sonde.si()->afc = afc; - } - if(di>520) { - // TODO - Serial.println("TOO MUCH DATA"); - break; - } - previous = millis(); // reset timeout after receiving data -#endif - } - value = sx1278.readRegister(REG_IRQ_FLAGS2); - } - Serial.printf("processed %d bytes before end/timeout\n", by); -#endif - - - -///// -#if 0 - int e = sx1278.receivePacketTimeout(1000, data+8); - if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; } //if timeout... return 1 - - printRaw(data, RS92MAXLEN); - //for(int i=0; i>7), CCCCC=rx[19:20] in decimal +