make use of LED :)
This commit is contained in:
parent
9d0fd046e1
commit
f0a92a6d39
|
|
@ -21,7 +21,6 @@
|
|||
#include "geteph.h"
|
||||
#include "rs92gps.h"
|
||||
|
||||
int LORA_LED = 9; // default POUT for LORA LED used as serial monitor
|
||||
int e;
|
||||
|
||||
enum MainState { ST_DECODER, ST_SPECTRUM, ST_WIFISCAN, ST_UPDATE };
|
||||
|
|
@ -883,12 +882,14 @@ void touchISR2();
|
|||
// Instead create a tast...
|
||||
|
||||
Ticker ticker;
|
||||
Ticker ledFlasher;
|
||||
|
||||
#define IS_TOUCH(x) (((x)!=255)&&((x)!=-1)&&((x)&128))
|
||||
void initTouch() {
|
||||
// also used for LED
|
||||
ticker.attach_ms(300, checkTouchStatus);
|
||||
|
||||
if ( !(IS_TOUCH(sonde.config.button_pin) || IS_TOUCH(sonde.config.button2_pin)) ) return; // no touch buttons configured
|
||||
|
||||
|
||||
/*
|
||||
* ** no. readTouch is not safe to use in ISR!
|
||||
so now using Ticker
|
||||
|
|
@ -897,8 +898,6 @@ void initTouch() {
|
|||
timerAlarmWrite(timer, 300000, true);
|
||||
timerAlarmEnable(timer);
|
||||
*/
|
||||
ticker.attach_ms(300, checkTouchStatus);
|
||||
|
||||
if ( IS_TOUCH(sonde.config.button_pin) ) {
|
||||
touchAttachInterrupt(sonde.config.button_pin & 0x7f, touchISR, 60);
|
||||
Serial.printf("Initializing touch 1 on pin %d\n", sonde.config.button_pin & 0x7f);
|
||||
|
|
@ -1037,6 +1036,15 @@ void checkTouchButton(Button & button) {
|
|||
}
|
||||
}
|
||||
|
||||
void ledOffCallback() {
|
||||
digitalWrite(sonde.config.led_pout, LOW);
|
||||
}
|
||||
void flashLed(int ms) {
|
||||
digitalWrite(sonde.config.led_pout, HIGH);
|
||||
ledFlasher.once_ms(ms, ledOffCallback);
|
||||
}
|
||||
|
||||
int doTouch = 0;
|
||||
void checkTouchStatus() {
|
||||
checkTouchButton(button1);
|
||||
checkTouchButton(button2);
|
||||
|
|
@ -1271,8 +1279,9 @@ void setup()
|
|||
digitalWrite(sonde.config.power_pout & 127, sonde.config.power_pout & 128 ? 1 : 0);
|
||||
}
|
||||
|
||||
LORA_LED = sonde.config.led_pout;
|
||||
pinMode(LORA_LED, OUTPUT);
|
||||
pinMode(sonde.config.led_pout, OUTPUT);
|
||||
digitalWrite(sonde.config.led_pout, HIGH);
|
||||
flashLed(1000); // testing
|
||||
|
||||
button1.pin = sonde.config.button_pin;
|
||||
button2.pin = sonde.config.button2_pin;
|
||||
|
|
|
|||
|
|
@ -233,7 +233,8 @@ const static float DEGMUL = 1.0/0xB60B60;
|
|||
#define RAD (PI/180)
|
||||
|
||||
|
||||
bool M10::decodeframeM10(uint8_t *data) {
|
||||
// ret: 1=frame ok; 2=frame with errors; 0=ignored frame (m10dop-alternativ)
|
||||
int M10::decodeframeM10(uint8_t *data) {
|
||||
int repairstep = 16;
|
||||
int repl = 0;
|
||||
bool crcok;
|
||||
|
|
@ -313,8 +314,9 @@ bool M10::decodeframeM10(uint8_t *data) {
|
|||
sonde.si()->validTime = true;
|
||||
} else {
|
||||
Serial.printf("data is %02x %02x %02x\n", data[0], data[1], data[2]);
|
||||
return 0;
|
||||
}
|
||||
return crcok;
|
||||
return crcok?1:2;
|
||||
}
|
||||
|
||||
static uint32_t rxdata;
|
||||
|
|
@ -369,8 +371,7 @@ void M10::processM10data(uint8_t dt)
|
|||
#endif
|
||||
if(rxp>=M10_FRAMELEN) {
|
||||
rxsearching = true;
|
||||
bool ok = decodeframeM10(dataptr);
|
||||
haveNewFrame = ok ? 1 : 2;
|
||||
haveNewFrame = decodeframeM10(dataptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -54,7 +54,7 @@ class M10
|
|||
private:
|
||||
void printRaw(uint8_t *data, int len);
|
||||
void processM10data(uint8_t data);
|
||||
bool decodeframeM10(uint8_t *data);
|
||||
int decodeframeM10(uint8_t *data);
|
||||
#if 0
|
||||
void stobyte92(uint8_t byte);
|
||||
void dogps(const uint8_t *sf, int sf_len,
|
||||
|
|
|
|||
|
|
@ -84,6 +84,7 @@ void Sonde::defaultConfig() {
|
|||
config.button_pin = 0;
|
||||
config.button2_pin = T4 + 128; // T4 == GPIO13
|
||||
config.power_pout = 21; // for Heltec v2
|
||||
config.led_pout = 2;
|
||||
Serial.println("Autoconfig: looks like TTGO v1 / Heltec v1/V2 board");
|
||||
} else {
|
||||
config.oled_sda = 21;
|
||||
|
|
@ -139,6 +140,7 @@ void Sonde::defaultConfig() {
|
|||
} else {
|
||||
config.button_pin = 2 + 128; // GPIO2 / T2
|
||||
config.button2_pin = 14 + 128; // GPIO14 / T6
|
||||
config.led_pout = 25;
|
||||
}
|
||||
}
|
||||
//
|
||||
|
|
@ -381,6 +383,8 @@ void Sonde::setup() {
|
|||
Serial.printf("AFC BW: %f RX BW: %f\n", afcbw, rxbw);
|
||||
}
|
||||
|
||||
extern void flashLed(int ms);
|
||||
|
||||
void Sonde::receive() {
|
||||
uint16_t res = 0;
|
||||
SondeInfo *si = &sondeList[rxtask.currentSonde];
|
||||
|
|
@ -402,11 +406,13 @@ void Sonde::receive() {
|
|||
|
||||
// state information for RX_TIMER / NORX_TIMER events
|
||||
if(res==0) { // RX OK
|
||||
flashLed(700);
|
||||
if(si->lastState != 1) {
|
||||
si->rxStart = millis();
|
||||
si->lastState = 1;
|
||||
}
|
||||
} else { // RX not ok
|
||||
if(res==RX_ERROR) flashLed(100);
|
||||
if(si->lastState != 0) {
|
||||
si->norxStart = millis();
|
||||
si->lastState = 0;
|
||||
|
|
|
|||
Loading…
Reference in New Issue