mirror of
https://github.com/fhem/fhem-mirror.git
synced 2025-04-07 19:04:20 +00:00
98_Arducounter.pm: bug fixes and firmware update
git-svn-id: https://svn.fhem.de/fhem/trunk@19808 2b470e98-0d58-463d-a4d8-8e2adae1ed80
This commit is contained in:
parent
1eb5a3500f
commit
afd9e4a3f7
@ -80,6 +80,7 @@
|
|||||||
# 2019-02-23 added maxHist attribute
|
# 2019-02-23 added maxHist attribute
|
||||||
# 2019-02-24 added documentation and better return value when get history has no data, option to pass a pinName to get history
|
# 2019-02-24 added documentation and better return value when get history has no data, option to pass a pinName to get history
|
||||||
# query new running config after configuring device
|
# query new running config after configuring device
|
||||||
|
# 2019-06-17 fix log messages and expose logRetries attribute
|
||||||
#
|
#
|
||||||
# ideas / todo:
|
# ideas / todo:
|
||||||
#
|
#
|
||||||
@ -103,7 +104,7 @@ use strict;
|
|||||||
use warnings;
|
use warnings;
|
||||||
use Time::HiRes qw(gettimeofday);
|
use Time::HiRes qw(gettimeofday);
|
||||||
|
|
||||||
my $ArduCounter_Version = '6.14 - 24.2.2019';
|
my $ArduCounter_Version = '6.15 - 17.6.2019';
|
||||||
|
|
||||||
|
|
||||||
my %ArduCounter_sets = (
|
my %ArduCounter_sets = (
|
||||||
@ -192,6 +193,7 @@ sub ArduCounter_Initialize($)
|
|||||||
'configDelay ' . # how many seconds to wait before sending config after reboot of board
|
'configDelay ' . # how many seconds to wait before sending config after reboot of board
|
||||||
'keepAliveDelay ' .
|
'keepAliveDelay ' .
|
||||||
'keepAliveTimeout ' .
|
'keepAliveTimeout ' .
|
||||||
|
'keepAliveRetries ' .
|
||||||
'nextOpenDelay ' .
|
'nextOpenDelay ' .
|
||||||
'silentReconnect:0,1 ' .
|
'silentReconnect:0,1 ' .
|
||||||
'openTimeout ' .
|
'openTimeout ' .
|
||||||
@ -538,14 +540,14 @@ sub ArduCounter_AliveTimeout($)
|
|||||||
my $param = shift;
|
my $param = shift;
|
||||||
my (undef,$name) = split(/:/,$param);
|
my (undef,$name) = split(/:/,$param);
|
||||||
my $hash = $defs{$name};
|
my $hash = $defs{$name};
|
||||||
Log3 $name, 3, "$name: device didn't reply to k(eeepAlive), setting to disconnected and try to reopen";
|
|
||||||
delete $hash->{WaitForAlive};
|
delete $hash->{WaitForAlive};
|
||||||
|
|
||||||
$hash->{KeepAliveRetries} = 0 if (!$hash->{KeepAliveRetries});
|
$hash->{KeepAliveRetries} = 0 if (!$hash->{KeepAliveRetries});
|
||||||
|
|
||||||
if (++$hash->{KeepAliveRetries} > AttrVal($name, "keepAliveRetries", 1)) {
|
if (++$hash->{KeepAliveRetries} > AttrVal($name, "keepAliveRetries", 1)) {
|
||||||
Log3 $name, 3, "$name: no retries left, setting device to disconnected";
|
Log3 $name, 3, "$name: device didn't reply to k(eeepAlive), no retries left, setting device to disconnected";
|
||||||
ArduCounter_Disconnected($hash); # set to Disconnected but let _Ready try to Reopen
|
ArduCounter_Disconnected($hash); # set to Disconnected but let _Ready try to Reopen
|
||||||
|
} else {
|
||||||
|
Log3 $name, 3, "$name: device didn't reply to k(eeepAlive), count=$hash->{KeepAliveRetries}";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -2070,7 +2072,13 @@ sub ArduCounter_ReadAnswer($$)
|
|||||||
<code>
|
<code>
|
||||||
attr myCounter keepAliveTimeout 3
|
attr myCounter keepAliveTimeout 3
|
||||||
</code>
|
</code>
|
||||||
|
<li><b>keepAliveRetries</b></li>
|
||||||
|
defines how often sending a keepalive is retried before the connection is closed and reopened.<br>
|
||||||
|
It defaults to 2.<br>
|
||||||
|
Example:
|
||||||
|
<code>
|
||||||
|
attr myCounter keepAliveRetries 3
|
||||||
|
</code>
|
||||||
<li><b>nextOpenDelay</b></li>
|
<li><b>nextOpenDelay</b></li>
|
||||||
defines the time that the module waits before retrying to open a disconnected tcp connection. <br>
|
defines the time that the module waits before retrying to open a disconnected tcp connection. <br>
|
||||||
This defaults to 60 seconds.<br>
|
This defaults to 60 seconds.<br>
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -1,804 +0,0 @@
|
|||||||
/*
|
|
||||||
* Sketch for counting impulses in a defined interval
|
|
||||||
* e.g. for power meters with an s0 interface that can be
|
|
||||||
* connected to an input of an arduino board
|
|
||||||
*
|
|
||||||
* the sketch uses pin change interrupts which can be anabled
|
|
||||||
* for any of the inputs on e.g. an arduino uno or a jeenode
|
|
||||||
*
|
|
||||||
* the pin change Interrupt handling used here
|
|
||||||
* is based on the arduino playground example on PCINT:
|
|
||||||
* http://playground.arduino.cc/Main/PcInt
|
|
||||||
*
|
|
||||||
* Refer to avr-gcc header files, arduino source and atmega datasheet.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Pin to interrupt map:
|
|
||||||
* D0-D7 = PCINT 16-23 = PCIR2 = PD = PCIE2 = pcmsk2
|
|
||||||
* D8-D13 = PCINT 0-5 = PCIR0 = PB = PCIE0 = pcmsk0
|
|
||||||
* A0-A5 (D14-D19) = PCINT 8-13 = PCIR1 = PC = PCIE1 = pcmsk1
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
Changes:
|
|
||||||
V1.2
|
|
||||||
27.10.16 - use noInterrupts in report()
|
|
||||||
- avoid reporting very short timeDiff in case of very slow impulses after a report
|
|
||||||
- now reporting is delayed if impulses happened only within in intervalSml
|
|
||||||
- reporting is also delayed if less than countMin pulses counted
|
|
||||||
- extend command "int" for optional intervalSml and countMin
|
|
||||||
29.10.16 - allow interval Min >= Max or Sml > Min
|
|
||||||
which changes behavior to take fixed calculation interval instead of timeDiff between pulses
|
|
||||||
-> if intervalMin = intervalMax, counting will allways follow the reporting interval
|
|
||||||
3.11.16 - more noInterrupt blocks when accessing the non byte volatiles in report
|
|
||||||
V1.3
|
|
||||||
4.11.16 - check min pulse width and add more output,
|
|
||||||
- prefix show output with M
|
|
||||||
V1.4
|
|
||||||
10.11.16 - restructure add Cmd
|
|
||||||
- change syntax for specifying minPulseLengh
|
|
||||||
- res (reset) command
|
|
||||||
V1.6
|
|
||||||
13.12.16 - new startup message logic?, newline before first communication?
|
|
||||||
18.12.16 - replace all code containing Strings, new communication syntax and parsing from Jeelink code
|
|
||||||
V1.7
|
|
||||||
2.1.17 - change message syntax again, report time as well, first and last impulse are reported relative to start of intervall
|
|
||||||
not start of reporting intervall
|
|
||||||
V1.8
|
|
||||||
4.1.17 - fixed a missing break in the case statement for pin definition
|
|
||||||
5.1.17 - cleanup debug logging
|
|
||||||
|
|
||||||
ToDo / Ideas:
|
|
||||||
|
|
||||||
new index scheme to save memory:
|
|
||||||
array to map from pcintPin to new index, limit allowed pins.
|
|
||||||
unused pcintpins point to -1 and vomment states arduino pin number
|
|
||||||
insread of allowedPins array use new function from aPin to pcintPin
|
|
||||||
and then look up in new array for index or -1
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "pins_arduino.h"
|
|
||||||
|
|
||||||
const char versionStr[] PROGMEM = "ArduCounter V1.8";
|
|
||||||
const char errorStr[] PROGMEM = "Error: ";
|
|
||||||
|
|
||||||
#define enablePulseLenChecking 1
|
|
||||||
|
|
||||||
#define SERIAL_SPEED 38400
|
|
||||||
#define MAX_ARDUINO_PIN 24
|
|
||||||
#define MAX_PCINT_PIN 24
|
|
||||||
#define MAX_INPUT_NUM 8
|
|
||||||
|
|
||||||
/* arduino pins that are typically ok to use
|
|
||||||
* (some are left out because they are used
|
|
||||||
* as reset, serial, led or other things on most boards) */
|
|
||||||
byte allowedPins[MAX_ARDUINO_PIN] =
|
|
||||||
{ 0, 0, 0, 3, 4, 5, 6, 7,
|
|
||||||
0, 9, 10, 11, 12, 0,
|
|
||||||
14, 15, 16, 17, 0, 0};
|
|
||||||
|
|
||||||
|
|
||||||
/* Pin change mask for each chip port */
|
|
||||||
volatile uint8_t *port_to_pcmask[] = {
|
|
||||||
&PCMSK0,
|
|
||||||
&PCMSK1,
|
|
||||||
&PCMSK2
|
|
||||||
};
|
|
||||||
|
|
||||||
/* last PIN States to detect individual pin changes in ISR */
|
|
||||||
volatile static uint8_t PCintLast[3];
|
|
||||||
|
|
||||||
unsigned long intervalMin = 30000; // default 30 sec - report after this time if nothing else delays it
|
|
||||||
unsigned long intervalMax = 60000; // default 60 sec - report after this time if it didin't happen before
|
|
||||||
unsigned long intervalSml = 2000; // default 2 secs - continue count if timeDiff is less and intervalMax not over
|
|
||||||
unsigned int countMin = 1; // continue counting if count is less than this and intervalMax not over
|
|
||||||
|
|
||||||
unsigned long timeNextReport;
|
|
||||||
|
|
||||||
/* index to the following arrays is the internal PCINT pin number, not the arduino
|
|
||||||
* pin number because the PCINT pin number corresponds to the physical ports
|
|
||||||
* and this saves time for mapping to the arduino numbers
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* pin change mode (RISING etc.) as parameter for ISR */
|
|
||||||
byte PCintMode[MAX_PCINT_PIN];
|
|
||||||
/* mode for timing pulse length - derived from PCintMode (RISING etc. */
|
|
||||||
byte PulseMode[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* pin number for PCINT number if active - otherwise -1 */
|
|
||||||
char PCintActivePin[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* did we get first interrupt yet? */
|
|
||||||
volatile boolean initialized[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* individual counter for each real pin */
|
|
||||||
volatile unsigned long counter[MAX_PCINT_PIN];
|
|
||||||
/* count at last report to get difference */
|
|
||||||
unsigned long lastCount[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
/* individual reject counter for each real pin */
|
|
||||||
volatile unsigned int rejectCounter[MAX_PCINT_PIN];
|
|
||||||
unsigned int lastRejCount[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at last interrupt when signal was rising (for filtering with min pulse length) */
|
|
||||||
volatile unsigned long lastPulseStart[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at last interrupt when signal was falling (for filtering with min pulse length) */
|
|
||||||
volatile unsigned long lastPulseEnd[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* minimal pulse length in millis */
|
|
||||||
/* specified instead of rising or falling. isr needs to check change anyway */
|
|
||||||
unsigned int pulseWidthMin[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* sum of pulse lengths for average output */
|
|
||||||
volatile unsigned long pulseWidthSum[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* start of pulse for measuring length */
|
|
||||||
byte pulseWidthStart[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* millis at first interrupt for current calculation
|
|
||||||
* (is also last interrupt of old interval) */
|
|
||||||
volatile unsigned long startTime[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at last interrupt */
|
|
||||||
volatile unsigned long lastTime[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at first interrupt in a reporting cycle */
|
|
||||||
volatile unsigned long startTimeRepInt[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
|
|
||||||
/* millis at last report
|
|
||||||
* to find out when maxInterval is over
|
|
||||||
* and report has to be done even if
|
|
||||||
* no impulses were counted */
|
|
||||||
unsigned long lastReport[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
unsigned int commandData[MAX_INPUT_NUM];
|
|
||||||
byte commandDataPointer = 0;
|
|
||||||
|
|
||||||
|
|
||||||
int digitalPinToPcIntPin(uint8_t aPin) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (index for most arrays)
|
|
||||||
uint8_t port = digitalPinToPort(aPin) - 2; // port that this arduno pin belongs to for enabling interrupts
|
|
||||||
|
|
||||||
if (port == 1) { // now calculate the PCINT pin number that corresponds to the arduino pin number
|
|
||||||
pcintPin = aPin - 6; // port 1: PC0-PC5 (A0-A5 or D14-D19) is PCINT 8-13 (PC6 is reset)
|
|
||||||
} else { // arduino numbering continues at D14 since PB6/PB7 are used for other things
|
|
||||||
pcintPin = port * 8 + (aPin % 8); // port 0: PB0-PB5 (D8-D13) is PCINT 0-5 (PB6/PB7 is crystal)
|
|
||||||
} // port 2: PD0-PD7 (D0-D7) is PCINT 16-23
|
|
||||||
return pcintPin;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* Add a pin to be handled */
|
|
||||||
byte AddPinChangeInterrupt(uint8_t aPin) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (used as index for most arrays)
|
|
||||||
volatile uint8_t *pcmask; // pointer to PCMSK0 or 1 or 2 depending on the port corresponding to the pin
|
|
||||||
|
|
||||||
uint8_t bit = digitalPinToBitMask(aPin); // bit in PCMSK to enable pin change interrupt for this arduino pin
|
|
||||||
uint8_t port = digitalPinToPort(aPin); // port that this arduno pin belongs to for enabling interrupts
|
|
||||||
|
|
||||||
if (port == NOT_A_PORT)
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
port -= 2;
|
|
||||||
pcmask = port_to_pcmask[port]; // point to PCMSK0 or 1 or 2 depending on the port corresponding to the pin
|
|
||||||
*pcmask |= bit; // set the pin change interrupt mask through a pointer to PCMSK0 or 1 or 2
|
|
||||||
PCICR |= 0x01 << port; // enable the interrupt
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* Remove a pin to be handled */
|
|
||||||
byte RemovePinChangeInterrupt(uint8_t aPin) {
|
|
||||||
uint8_t pcintPin;
|
|
||||||
volatile uint8_t *pcmask;
|
|
||||||
|
|
||||||
uint8_t bit = digitalPinToBitMask(aPin);
|
|
||||||
uint8_t port = digitalPinToPort(aPin);
|
|
||||||
|
|
||||||
if (port == NOT_A_PORT)
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
port -= 2;
|
|
||||||
pcmask = port_to_pcmask[port];
|
|
||||||
*pcmask &= ~bit; // disable the mask.
|
|
||||||
if (*pcmask == 0) { // if that's the last one, disable the interrupt.
|
|
||||||
PCICR &= ~(0x01 << port);
|
|
||||||
}
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void PrintErrorMsg() {
|
|
||||||
int len = strlen_P(errorStr);
|
|
||||||
char myChar;
|
|
||||||
for (unsigned char k = 0; k < len; k++) {
|
|
||||||
myChar = pgm_read_byte_near(errorStr + k);
|
|
||||||
Serial.print(myChar);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void printVersion() {
|
|
||||||
int len = strlen_P(versionStr);
|
|
||||||
char myChar;
|
|
||||||
for (unsigned char k = 0; k < len; k++) {
|
|
||||||
myChar = pgm_read_byte_near(versionStr + k);
|
|
||||||
Serial.print(myChar);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
common interrupt handler. "port" is the PCINT port number (0-2)
|
|
||||||
|
|
||||||
do counting and set start / end time of interval.
|
|
||||||
reporting is not triggered from here.
|
|
||||||
|
|
||||||
only here counter[] is modified
|
|
||||||
lastTime[] is set here and in report
|
|
||||||
startTime[] is set in case a pin was not initialized yet and in report
|
|
||||||
*/
|
|
||||||
static void PCint(uint8_t port) {
|
|
||||||
uint8_t bit;
|
|
||||||
uint8_t curr;
|
|
||||||
uint8_t mask;
|
|
||||||
uint8_t pcintPin;
|
|
||||||
unsigned long now = millis();
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
unsigned long len, gap;
|
|
||||||
#endif
|
|
||||||
// get the pin states for the indicated port.
|
|
||||||
curr = *portInputRegister(port+2); // current pin states at port
|
|
||||||
mask = curr ^ PCintLast[port]; // xor gets bits that are different
|
|
||||||
PCintLast[port] = curr; // store new pin state for next interrupt
|
|
||||||
|
|
||||||
if ((mask &= *port_to_pcmask[port]) == 0) // mask is pins that have changed. screen out non pcint pins.
|
|
||||||
return; /* no handled pin changed */
|
|
||||||
|
|
||||||
for (uint8_t i=0; i < 8; i++) {
|
|
||||||
bit = 0x01 << i; // loop over each pin that changed
|
|
||||||
if (bit & mask) { // did this pin change?
|
|
||||||
pcintPin = port * 8 + i; // pcint pin numbers follow the bits, only arduino pin nums are special
|
|
||||||
|
|
||||||
// count if mode is CHANGE, or if RISING and bit is high, or if mode is FALLING and bit is low.
|
|
||||||
if ((PCintMode[pcintPin] == CHANGE
|
|
||||||
|| ((PCintMode[pcintPin] == RISING) && (curr & bit))
|
|
||||||
|| ((PCintMode[pcintPin] == FALLING) && !(curr & bit)))) {
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
if (pulseWidthMin[pcintPin]) { // check minimal pulse length and gap
|
|
||||||
if ( ( (curr & bit) && pulseWidthStart[pcintPin] == RISING)
|
|
||||||
|| (!(curr & bit) && pulseWidthStart[pcintPin] == FALLING)) { // edge does fit defined start
|
|
||||||
lastPulseStart[pcintPin] = now;
|
|
||||||
continue;
|
|
||||||
} else { // End of defined pulse
|
|
||||||
gap = lastPulseStart[pcintPin] - lastPulseEnd[pcintPin];
|
|
||||||
len = now - lastPulseStart[pcintPin];
|
|
||||||
lastPulseEnd[pcintPin] = now;
|
|
||||||
if (len < pulseWidthMin[pcintPin] || gap < pulseWidthMin[pcintPin]) {
|
|
||||||
rejectCounter[pcintPin]++; // pulse too short
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
pulseWidthSum[pcintPin] += len; // for average calculation
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
lastTime[pcintPin] = now; // remember time of in case pulse will be the last in the interval
|
|
||||||
if (!startTimeRepInt[pcintPin]) startTimeRepInt[pcintPin] = now; // time of first impulse in this reporting interval
|
|
||||||
if (initialized[pcintPin]) {
|
|
||||||
counter[pcintPin]++; // count
|
|
||||||
} else {
|
|
||||||
startTime[pcintPin] = lastTime[pcintPin]; // if this is the very first impulse on this pin -> start interval now
|
|
||||||
initialized[pcintPin] = true; // and start counting the next impulse (so far counter is 0)
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
report count and time for pins that are between min and max interval
|
|
||||||
|
|
||||||
lastCount[] is only modified here (count at time of last reporting)
|
|
||||||
lastTime[] is modified here and in ISR - disable interrupts in critcal moments to avoid garbage in var
|
|
||||||
startTime[] is modified only here (or for very first Interrupt in ISR) -> no problem.
|
|
||||||
*/
|
|
||||||
void report() {
|
|
||||||
int aPin;
|
|
||||||
unsigned long count, countDiff;
|
|
||||||
unsigned long timeDiff, now;
|
|
||||||
unsigned long startT, endT;
|
|
||||||
unsigned long avgLen;
|
|
||||||
now = millis();
|
|
||||||
for (int pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++) { // go through all observed pins as PCINT pin number
|
|
||||||
aPin = PCintActivePin[pcintPin]; // take saved arduino pin number
|
|
||||||
if (aPin < 0) continue; // -1 means pin is not active for reporting
|
|
||||||
noInterrupts();
|
|
||||||
startT = startTime[pcintPin];
|
|
||||||
endT = lastTime[pcintPin];
|
|
||||||
count = counter[pcintPin]; // get current counter
|
|
||||||
interrupts();
|
|
||||||
|
|
||||||
timeDiff = endT - startT; // time between first and last impulse during interval
|
|
||||||
countDiff = count - lastCount[pcintPin]; // how many impulses since last report? (works with wrapping)
|
|
||||||
|
|
||||||
if((long)(now - (lastReport[pcintPin] + intervalMax)) >= 0) { // intervalMax is over
|
|
||||||
if ((countDiff >= countMin) && (timeDiff > intervalSml) && (intervalMin != intervalMax)) {
|
|
||||||
// normal procedure
|
|
||||||
lastCount[pcintPin] = count; // remember current count for next interval
|
|
||||||
noInterrupts();
|
|
||||||
startTime[pcintPin] = endT; // time of last impulse in this interval becomes also time of first impulse in next
|
|
||||||
interrupts();
|
|
||||||
} else {
|
|
||||||
// nothing counted or counts happened during a fraction of intervalMin only
|
|
||||||
noInterrupts();
|
|
||||||
lastTime[pcintPin] = now; // don't calculate with last impulse, use now instead
|
|
||||||
startTime[pcintPin] = now; // start a new interval for next report now
|
|
||||||
interrupts();
|
|
||||||
lastCount[pcintPin] = count; // remember current count for next interval
|
|
||||||
timeDiff = now - startT; // special handling - calculation ends now instead of last impulse
|
|
||||||
}
|
|
||||||
} else if((long)(now - (lastReport[pcintPin] + intervalMin)) >= 0) { // minInterval has elapsed
|
|
||||||
if ((countDiff >= countMin) && (timeDiff > intervalSml)) {
|
|
||||||
// normal procedure
|
|
||||||
lastCount[pcintPin] = count; // remember current count for next interval
|
|
||||||
noInterrupts();
|
|
||||||
startTime[pcintPin] = endT; // time of last impulse in this interval becomes also time of first impulse in next
|
|
||||||
interrupts();
|
|
||||||
} else continue; // not enough counted - wait
|
|
||||||
} else continue; // intervalMin not over - wait
|
|
||||||
|
|
||||||
Serial.print(F("R")); // R Report
|
|
||||||
Serial.print(aPin);
|
|
||||||
Serial.print(F(" C")); // C - Count
|
|
||||||
Serial.print(count);
|
|
||||||
Serial.print(F(" D")); // D - Count Diff
|
|
||||||
Serial.print(countDiff);
|
|
||||||
Serial.print(F(" T")); // T - Time
|
|
||||||
Serial.print(timeDiff);
|
|
||||||
Serial.print(F(" N")); // N - now
|
|
||||||
Serial.print((long)now);
|
|
||||||
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
// rejected count ausgeben
|
|
||||||
// evt auch noch average pulse len und gap len
|
|
||||||
if (pulseWidthMin[pcintPin]) { // check minimal pulse length and gap
|
|
||||||
Serial.print(F(" X")); // X Reject
|
|
||||||
Serial.print(rejectCounter[pcintPin] - lastRejCount[pcintPin]);
|
|
||||||
noInterrupts();
|
|
||||||
lastRejCount[pcintPin] = rejectCounter[pcintPin];
|
|
||||||
interrupts();
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (countDiff) {
|
|
||||||
Serial.print(F(" F")); // F - first impulse after the one that started the interval
|
|
||||||
Serial.print((long)startTimeRepInt[pcintPin] - startT);
|
|
||||||
Serial.print(F(" L")); // L - last impulse - marking the end of this interval
|
|
||||||
Serial.print((long)endT - startT);
|
|
||||||
startTimeRepInt[pcintPin] = 0;
|
|
||||||
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
if (pulseWidthMin[pcintPin]) {// check minimal pulse length and gap
|
|
||||||
noInterrupts();
|
|
||||||
avgLen = pulseWidthSum[pcintPin] / countDiff;
|
|
||||||
pulseWidthSum[pcintPin] = 0;
|
|
||||||
interrupts();
|
|
||||||
Serial.print(F(" A"));
|
|
||||||
Serial.print(avgLen);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
Serial.println();
|
|
||||||
lastReport[pcintPin] = now; // remember when we reported
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* print status for one pin */
|
|
||||||
void showPin(byte pcintPin) {
|
|
||||||
unsigned long newCount;
|
|
||||||
unsigned long countDiff;
|
|
||||||
unsigned long timeDiff;
|
|
||||||
unsigned long avgLen;
|
|
||||||
|
|
||||||
timeDiff = lastTime[pcintPin] - startTime[pcintPin];
|
|
||||||
newCount = counter[pcintPin];
|
|
||||||
countDiff = newCount - lastCount[pcintPin];
|
|
||||||
if (!timeDiff)
|
|
||||||
timeDiff = millis() - startTime[pcintPin];
|
|
||||||
|
|
||||||
Serial.print(F("PCInt pin "));
|
|
||||||
Serial.print(pcintPin);
|
|
||||||
|
|
||||||
Serial.print(F(", iMode "));
|
|
||||||
switch (PCintMode[pcintPin]) {
|
|
||||||
case RISING: Serial.print(F("rising")); break;
|
|
||||||
case FALLING: Serial.print(F("falling")); break;
|
|
||||||
case CHANGE: Serial.print(F("change")); break;
|
|
||||||
}
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
if (pulseWidthMin[pcintPin] > 0) {
|
|
||||||
Serial.print(F(", min len "));
|
|
||||||
Serial.print(pulseWidthMin[pcintPin]);
|
|
||||||
Serial.print(F(" ms"));
|
|
||||||
switch (pulseWidthStart[pcintPin]) {
|
|
||||||
case RISING: Serial.print(F(" rising")); break;
|
|
||||||
case FALLING: Serial.print(F(" falling")); break;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
Serial.print(F(", no min len"));
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
Serial.print(F(", count "));
|
|
||||||
Serial.print(newCount);
|
|
||||||
Serial.print(F(" (+"));
|
|
||||||
Serial.print(countDiff);
|
|
||||||
Serial.print(F(") in "));
|
|
||||||
Serial.print(timeDiff);
|
|
||||||
Serial.print(F(" ms"));
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
// rejected count ausgeben
|
|
||||||
// evt auch noch average pulse len und gap len
|
|
||||||
if (pulseWidthMin[pcintPin]) { // check minimal pulse length and gap
|
|
||||||
Serial.print(F(" Rej "));
|
|
||||||
Serial.print(rejectCounter[pcintPin] - lastRejCount[pcintPin]);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
if (countDiff) {
|
|
||||||
Serial.println();
|
|
||||||
Serial.print(F("M first at "));
|
|
||||||
Serial.print((long)startTimeRepInt[pcintPin] - lastReport[pcintPin]);
|
|
||||||
Serial.print(F(", last at "));
|
|
||||||
Serial.print((long)lastTime[pcintPin] - lastReport[pcintPin]);
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
noInterrupts();
|
|
||||||
avgLen = pulseWidthSum[pcintPin] / countDiff;
|
|
||||||
interrupts();
|
|
||||||
Serial.print(F(", avg len "));
|
|
||||||
Serial.print(avgLen);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* give status report in between if requested over serial input */
|
|
||||||
void showCmd() {
|
|
||||||
unsigned long newCount;
|
|
||||||
unsigned long countDiff;
|
|
||||||
unsigned long timeDiff;
|
|
||||||
unsigned long avgLen;
|
|
||||||
char myChar;
|
|
||||||
|
|
||||||
Serial.print(F("M Status: "));
|
|
||||||
printVersion();
|
|
||||||
Serial.println();
|
|
||||||
Serial.print(F("M normal interval "));
|
|
||||||
Serial.println(intervalMin);
|
|
||||||
Serial.print(F("M max interval "));
|
|
||||||
Serial.println(intervalMax);
|
|
||||||
Serial.print(F("M min interval "));
|
|
||||||
Serial.println(intervalSml);
|
|
||||||
Serial.print(F("M min count "));
|
|
||||||
Serial.println(countMin);
|
|
||||||
|
|
||||||
for (byte pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++) {
|
|
||||||
int aPin = PCintActivePin[pcintPin];
|
|
||||||
if (aPin != -1) {
|
|
||||||
timeDiff = lastTime[pcintPin] - startTime[pcintPin];
|
|
||||||
newCount = counter[pcintPin];
|
|
||||||
countDiff = newCount - lastCount[pcintPin];
|
|
||||||
if (!timeDiff)
|
|
||||||
timeDiff = millis() - startTime[pcintPin];
|
|
||||||
Serial.print(F("M pin "));
|
|
||||||
Serial.print(aPin);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
showPin(pcintPin);
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Serial.print(F("M Next report in "));
|
|
||||||
Serial.print(timeNextReport - millis());
|
|
||||||
Serial.print(F(" Milliseconds"));
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
handle add command.
|
|
||||||
*/
|
|
||||||
void addCmd(unsigned int *values, byte size) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (used as index for most arrays)
|
|
||||||
byte mode;
|
|
||||||
unsigned int pw;
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
//Serial.println(F("M Add called"));
|
|
||||||
int aPin = values[0];
|
|
||||||
pcintPin = digitalPinToPcIntPin(aPin);
|
|
||||||
if (aPin >= MAX_ARDUINO_PIN || aPin < 1
|
|
||||||
|| allowedPins[aPin] == 0 || pcintPin > MAX_PCINT_PIN) {
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("Illegal pin specification "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
return;
|
|
||||||
};
|
|
||||||
|
|
||||||
switch (values[1]) {
|
|
||||||
case 2:
|
|
||||||
mode = FALLING;
|
|
||||||
pulseWidthStart[pcintPin] = FALLING;
|
|
||||||
break;
|
|
||||||
case 3:
|
|
||||||
mode = RISING;
|
|
||||||
pulseWidthStart[pcintPin] = RISING;
|
|
||||||
break;
|
|
||||||
case 1:
|
|
||||||
mode = CHANGE;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("Illegal pin specification "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
}
|
|
||||||
|
|
||||||
pinMode (aPin, INPUT);
|
|
||||||
if (values[2]) {
|
|
||||||
digitalWrite (aPin, HIGH); // enable pullup resistor
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
PulseMode[pcintPin] = mode; // specified mode also defines pulse level in this case
|
|
||||||
if (values[3] > 0) {
|
|
||||||
pw = values[3];
|
|
||||||
mode = CHANGE;
|
|
||||||
} else {
|
|
||||||
pw = 0;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (!AddPinChangeInterrupt(aPin)) { // add Pin Change Interrupt
|
|
||||||
PrintErrorMsg(); Serial.println(F("AddInt"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
PCintMode[pcintPin] = mode; // save mode for ISR which uses the pcintPin as index
|
|
||||||
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
pulseWidthMin[pcintPin] = pw; // minimal pulse width in millis, 3 if not specified n add cmd
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (PCintActivePin[pcintPin] != aPin) { // in case this pin is already active counting
|
|
||||||
PCintActivePin[pcintPin] = aPin; // save real arduino pin number and flag this pin as active for reporting
|
|
||||||
initialized[pcintPin] = false; // initialize arrays for this pin
|
|
||||||
counter[pcintPin] = 0;
|
|
||||||
lastCount[pcintPin] = 0;
|
|
||||||
startTime[pcintPin] = now;
|
|
||||||
lastTime[pcintPin] = now;
|
|
||||||
lastReport[pcintPin] = now;
|
|
||||||
}
|
|
||||||
Serial.print(F("M defined pin "));
|
|
||||||
Serial.print(aPin);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
showPin(pcintPin);
|
|
||||||
Serial.println();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
handle rem command.
|
|
||||||
*/
|
|
||||||
void removeCmd(unsigned int *values, byte size) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (used as index for most arrays)
|
|
||||||
int aPin = values[0];
|
|
||||||
pcintPin = digitalPinToPcIntPin(aPin);
|
|
||||||
if (aPin >= MAX_ARDUINO_PIN || aPin < 1
|
|
||||||
|| allowedPins[aPin] == 0 || pcintPin > MAX_PCINT_PIN) {
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("Illegal pin specification "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
return;
|
|
||||||
};
|
|
||||||
|
|
||||||
if (!RemovePinChangeInterrupt(aPin)) {
|
|
||||||
PrintErrorMsg(); Serial.println(F("RemInt"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
PCintActivePin[pcintPin] = -1;
|
|
||||||
initialized[pcintPin] = false; // reset for next add
|
|
||||||
counter[pcintPin] = 0;
|
|
||||||
lastCount[pcintPin] = 0;
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
pulseWidthMin[pcintPin] = 0;
|
|
||||||
lastRejCount[pcintPin] = 0;
|
|
||||||
rejectCounter[pcintPin] = 0;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
Serial.print(F("M removed "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void intervalCmd(unsigned int *values, byte size) {
|
|
||||||
if (size < 4) {
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("size"));
|
|
||||||
Serial.println();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
if (values[0] < 1 || values[0] > 3600) {
|
|
||||||
PrintErrorMsg(); Serial.println(values[0]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
intervalMin = (long)values[0] * 1000;
|
|
||||||
if (millis() + intervalMin < timeNextReport)
|
|
||||||
timeNextReport = millis() + intervalMin;
|
|
||||||
|
|
||||||
if (values[1] < 1 || values[1] > 3600) {
|
|
||||||
PrintErrorMsg(); Serial.println(values[1]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
intervalMax = (long)values[1]* 1000;
|
|
||||||
|
|
||||||
if (values[2] > 3600) {
|
|
||||||
PrintErrorMsg(); Serial.println(values[2]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
if (values[2] > 0) {
|
|
||||||
intervalSml = (long)values[2] * 1000;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (values[3]> 0) {
|
|
||||||
countMin = values[3];
|
|
||||||
}
|
|
||||||
Serial.print(F("M intervals set to "));
|
|
||||||
Serial.print(values[0]);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
Serial.print(values[1]);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
Serial.print(values[2]);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
Serial.print(values[3]);
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void helloCmd() {
|
|
||||||
Serial.println();
|
|
||||||
printVersion();
|
|
||||||
Serial.println(F("Hello"));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static void HandleSerialPort(char c) {
|
|
||||||
static unsigned int value;
|
|
||||||
|
|
||||||
if (c == ',') {
|
|
||||||
if (commandDataPointer + 1 < MAX_INPUT_NUM) {
|
|
||||||
commandData[commandDataPointer++] = value;
|
|
||||||
value = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if ('0' <= c && c <= '9') {
|
|
||||||
value = 10 * value + c - '0';
|
|
||||||
}
|
|
||||||
else if ('a' <= c && c <= 'z') {
|
|
||||||
switch (c) {
|
|
||||||
case 'a':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
addCmd(commandData, ++commandDataPointer);
|
|
||||||
commandDataPointer = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'd':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
removeCmd(commandData, ++commandDataPointer);
|
|
||||||
commandDataPointer = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'i':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
intervalCmd(commandData, ++commandDataPointer);
|
|
||||||
commandDataPointer = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'r':
|
|
||||||
setup();
|
|
||||||
commandDataPointer = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 's':
|
|
||||||
showCmd();
|
|
||||||
commandDataPointer = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'h':
|
|
||||||
helloCmd();
|
|
||||||
commandDataPointer = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
commandDataPointer = 0;
|
|
||||||
//PrintErrorMsg(); Serial.println();
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
value = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
SIGNAL(PCINT0_vect) {
|
|
||||||
PCint(0);
|
|
||||||
}
|
|
||||||
SIGNAL(PCINT1_vect) {
|
|
||||||
PCint(1);
|
|
||||||
}
|
|
||||||
SIGNAL(PCINT2_vect) {
|
|
||||||
PCint(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void setup() {
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
for (int pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++) {
|
|
||||||
PCintActivePin[pcintPin] = -1; // set all pins to inactive (-1)
|
|
||||||
initialized[pcintPin] = false; // initialize arrays for this pin
|
|
||||||
counter[pcintPin] = 0;
|
|
||||||
lastCount[pcintPin] = 0;
|
|
||||||
startTime[pcintPin] = now;
|
|
||||||
lastTime[pcintPin] = now;
|
|
||||||
#ifdef enablePulseLenChecking
|
|
||||||
lastPulseStart[pcintPin] = now;
|
|
||||||
lastPulseEnd[pcintPin] = now;
|
|
||||||
pulseWidthMin[pcintPin] = 0;
|
|
||||||
rejectCounter[pcintPin] = 0;
|
|
||||||
lastRejCount[pcintPin] = 0;
|
|
||||||
#endif
|
|
||||||
lastReport[pcintPin] = now;
|
|
||||||
}
|
|
||||||
|
|
||||||
timeNextReport = millis() + intervalMin; // time for first output
|
|
||||||
Serial.begin(SERIAL_SPEED); // initialize serial
|
|
||||||
delay (500);
|
|
||||||
interrupts();
|
|
||||||
Serial.println();
|
|
||||||
printVersion();
|
|
||||||
Serial.println(F("Started"));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
Main Loop
|
|
||||||
checks if report should be called because timeNextReport is reached
|
|
||||||
or lastReport for one pin is older than intervalMax
|
|
||||||
timeNextReport is only set here (and when interval is changed / at setup)
|
|
||||||
*/
|
|
||||||
void loop() {
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
if (Serial.available()) {
|
|
||||||
HandleSerialPort(Serial.read());
|
|
||||||
}
|
|
||||||
boolean doReport = false; // check if report nedds to be called
|
|
||||||
if((long)(now - timeNextReport) >= 0) // works fine when millis wraps.
|
|
||||||
doReport = true; // intervalMin is over
|
|
||||||
else
|
|
||||||
for (byte pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++)
|
|
||||||
if (PCintActivePin[pcintPin] >= 0)
|
|
||||||
if((long)(now - (lastReport[pcintPin] + intervalMax)) >= 0)
|
|
||||||
doReport = true; // active pin has not been reported for langer than intervalMax
|
|
||||||
if (doReport) {
|
|
||||||
report();
|
|
||||||
timeNextReport = now + intervalMin; // do it again after intervalMin millis
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
@ -1,899 +0,0 @@
|
|||||||
/*
|
|
||||||
* Sketch for counting impulses in a defined interval
|
|
||||||
* e.g. for power meters with an s0 interface that can be
|
|
||||||
* connected to an input of an arduino board
|
|
||||||
*
|
|
||||||
* the sketch uses pin change interrupts which can be anabled
|
|
||||||
* for any of the inputs on e.g. an arduino uno or a jeenode
|
|
||||||
*
|
|
||||||
* the pin change Interrupt handling used here
|
|
||||||
* is based on the arduino playground example on PCINT:
|
|
||||||
* http://playground.arduino.cc/Main/PcInt
|
|
||||||
*
|
|
||||||
* Refer to avr-gcc header files, arduino source and atmega datasheet.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Pin to interrupt map:
|
|
||||||
* D0-D7 = PCINT 16-23 = PCIR2 = PD = PCIE2 = pcmsk2
|
|
||||||
* D8-D13 = PCINT 0-5 = PCIR0 = PB = PCIE0 = pcmsk0
|
|
||||||
* A0-A5 (D14-D19) = PCINT 8-13 = PCIR1 = PC = PCIE1 = pcmsk1
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* to test pin 4 with interval 10-20 sec do
|
|
||||||
* 4,2,1,30a
|
|
||||||
* 10,20,2,0i
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
Changes:
|
|
||||||
V1.2
|
|
||||||
27.10.16 - use noInterrupts in report()
|
|
||||||
- avoid reporting very short timeDiff in case of very slow impulses after a report
|
|
||||||
- now reporting is delayed if impulses happened only within in intervalSml
|
|
||||||
- reporting is also delayed if less than countMin pulses counted
|
|
||||||
- extend command "int" for optional intervalSml and countMin
|
|
||||||
29.10.16 - allow interval Min >= Max or Sml > Min
|
|
||||||
which changes behavior to take fixed calculation interval instead of timeDiff between pulses
|
|
||||||
-> if intervalMin = intervalMax, counting will allways follow the reporting interval
|
|
||||||
3.11.16 - more noInterrupt blocks when accessing the non byte volatiles in report
|
|
||||||
V1.3
|
|
||||||
4.11.16 - check min pulse width and add more output,
|
|
||||||
- prefix show output with M
|
|
||||||
V1.4
|
|
||||||
10.11.16 - restructure add Cmd
|
|
||||||
- change syntax for specifying minPulseLengh
|
|
||||||
- res (reset) command
|
|
||||||
V1.6
|
|
||||||
13.12.16 - new startup message logic?, newline before first communication?
|
|
||||||
18.12.16 - replace all code containing Strings, new communication syntax and parsing from Jeelink code
|
|
||||||
V1.7
|
|
||||||
2.1.17 - change message syntax again, report time as well, first and last impulse are reported relative to start of intervall
|
|
||||||
not start of reporting intervall
|
|
||||||
V1.8
|
|
||||||
4.1.17 - fixed a missing break in the case statement for pin definition
|
|
||||||
5.1.17 - cleanup debug logging
|
|
||||||
14.10.17 - fix a bug where last port state was not initialized after interrupt attached but this is necessary there
|
|
||||||
23.11.17 - beautify code, add comments, more debugging for users with problematic pulse creation devices
|
|
||||||
28.12.17 - better reportung of first pulse (even if only one pulse and countdiff is 0 but realdiff is 1)
|
|
||||||
30.12.17 - rewrite PCInt, new handling of min pulse length, pulse history ring
|
|
||||||
1.1.18 - check len in add command, allow pin 8 and 13
|
|
||||||
2.1.18 - add history per pin to report line, show negative starting times in show history
|
|
||||||
3.1.18 - little reporting fix (start pos of history report)
|
|
||||||
|
|
||||||
ToDo / Ideas:
|
|
||||||
|
|
||||||
new index scheme to save memory:
|
|
||||||
define new array to map from pcintPin to new index, limit allowed pins.
|
|
||||||
unused pcintpins point to -1 (or some other unused number < 0) and comment states arduino pin number
|
|
||||||
instead of allowedPins array use new function from aPin to pcintPin
|
|
||||||
and then look up in new array for index or -1
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "pins_arduino.h"
|
|
||||||
|
|
||||||
const char versionStr[] PROGMEM = "ArduCounter V2.05";
|
|
||||||
const char errorStr[] PROGMEM = "Error: ";
|
|
||||||
|
|
||||||
#define SERIAL_SPEED 38400
|
|
||||||
#define MAX_ARDUINO_PIN 24
|
|
||||||
#define MAX_PCINT_PIN 24
|
|
||||||
#define MAX_INPUT_NUM 8
|
|
||||||
#define MAX_HIST 20
|
|
||||||
|
|
||||||
/* arduino pins that are typically ok to use
|
|
||||||
* (some are left out because they are used
|
|
||||||
* as reset, serial, led or other things on most boards) */
|
|
||||||
byte allowedPins[MAX_ARDUINO_PIN] =
|
|
||||||
{ 0, 0, 0, 3, 4, 5, 6, 7,
|
|
||||||
8, 9, 10, 11, 12, 13,
|
|
||||||
14, 15, 16, 17, 0, 0};
|
|
||||||
|
|
||||||
|
|
||||||
/* Pin change mask for each chip port */
|
|
||||||
volatile uint8_t *port_to_pcmask[] = {
|
|
||||||
&PCMSK0,
|
|
||||||
&PCMSK1,
|
|
||||||
&PCMSK2
|
|
||||||
};
|
|
||||||
|
|
||||||
/* last PIN States to detect individual pin changes in ISR */
|
|
||||||
volatile static uint8_t PCintLast[3];
|
|
||||||
|
|
||||||
unsigned long intervalMin = 30000; // default 30 sec - report after this time if nothing else delays it
|
|
||||||
unsigned long intervalMax = 60000; // default 60 sec - report after this time if it didin't happen before
|
|
||||||
unsigned long intervalSml = 2000; // default 2 secs - continue count if timeDiff is less and intervalMax not over
|
|
||||||
unsigned int countMin = 1; // continue counting if count is less than this and intervalMax not over
|
|
||||||
|
|
||||||
unsigned long timeNextReport;
|
|
||||||
|
|
||||||
/* index to the following arrays is the internal PCINT pin number, not the arduino
|
|
||||||
* pin number because the PCINT pin number corresponds to the physical ports
|
|
||||||
* and this saves time for mapping to the arduino numbers
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* did we get first interrupt yet? */
|
|
||||||
volatile boolean initialized[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* individual counters for each real pin */
|
|
||||||
volatile unsigned long counter[MAX_PCINT_PIN];
|
|
||||||
volatile uint8_t counterIgn[MAX_PCINT_PIN]; // ignored first pulse after init
|
|
||||||
volatile unsigned int rejectCounter[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at last level change (for measuring pulse length) */
|
|
||||||
volatile unsigned long lastChange[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* last valid level */
|
|
||||||
volatile uint8_t lastLevel[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* sum of pulse lengths for average output */
|
|
||||||
volatile unsigned long pulseWidthSum[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
|
|
||||||
/* count at last report to get difference */
|
|
||||||
unsigned long lastCount[MAX_PCINT_PIN];
|
|
||||||
unsigned int lastRejCount[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* history ring */
|
|
||||||
volatile uint8_t histIndex;
|
|
||||||
volatile uint8_t histPin[MAX_HIST];
|
|
||||||
volatile uint8_t histLevel[MAX_HIST];
|
|
||||||
volatile unsigned long histTime[MAX_HIST];
|
|
||||||
volatile unsigned long histLen[MAX_HIST];
|
|
||||||
volatile char histAct[MAX_HIST];
|
|
||||||
//volatile uint8_t histI1[MAX_HIST];
|
|
||||||
|
|
||||||
|
|
||||||
/* real arduino pin number for PCINT number if active - otherwise 0 */
|
|
||||||
uint8_t PCintActivePin[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* pin change mode (RISING etc.) as parameter for ISR */
|
|
||||||
uint8_t PCintMode[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* minimal pulse length in millis for filtering */
|
|
||||||
unsigned int pulseWidthMin[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* start of pulse for measuring length */
|
|
||||||
uint8_t pulseWidthStart[MAX_PCINT_PIN]; // FALLING or RISING as defined for each pin
|
|
||||||
|
|
||||||
/* start and end of an interval - typically set by first / last pulse */
|
|
||||||
volatile unsigned long intervalStart[MAX_PCINT_PIN];
|
|
||||||
volatile unsigned long intervalEnd[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at first interrupt in a reporting cycle */
|
|
||||||
volatile unsigned long firstPulse[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* millis at last report
|
|
||||||
* to find out when maxInterval is over
|
|
||||||
* and report has to be done even if
|
|
||||||
* no impulses were counted */
|
|
||||||
unsigned long lastReport[MAX_PCINT_PIN];
|
|
||||||
|
|
||||||
/* input data over serial port */
|
|
||||||
unsigned int commandData[MAX_INPUT_NUM];
|
|
||||||
uint8_t commandDataPointer = 0;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
int digitalPinToPcIntPin(uint8_t aPin) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (index for most arrays)
|
|
||||||
uint8_t portIdx = digitalPinToPort(aPin)-2; // index of port that this arduno pin belongs to for enabling interrupts
|
|
||||||
// since the macro maps to defines PB(=2), PC(=3) and PD(=4), we subtract 2
|
|
||||||
// to use the result as array index in this sketch
|
|
||||||
|
|
||||||
if (portIdx == 1) { // now calculate the PCINT pin number that corresponds to the arduino pin number
|
|
||||||
pcintPin = aPin - 6; // portIdx 1: PC0-PC5 (A0-A5 or D14-D19) is PCINT 8-13 (PC6 is reset)
|
|
||||||
} else { // arduino numbering continues at D14 since PB6/PB7 are used for other things
|
|
||||||
pcintPin = portIdx*8 + (aPin % 8); // portIdx 0: PB0-PB5 (D8-D13) is PCINT 0-5 (PB6/PB7 is crystal)
|
|
||||||
} // portIdx 2: PD0-PD7 (D0-D7) is PCINT 16-23
|
|
||||||
return pcintPin;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* Add a pin to be handled */
|
|
||||||
byte AddPinChangeInterrupt(uint8_t aPin) {
|
|
||||||
volatile uint8_t *pcmask; // pointer to PCMSK0 or 1 or 2 depending on the port corresponding to the pin
|
|
||||||
|
|
||||||
uint8_t bitM = digitalPinToBitMask(aPin); // mask to bit in PCMSK to enable pin change interrupt for this arduino pin
|
|
||||||
uint8_t port = digitalPinToPort(aPin); // port that this arduno pin belongs to for enabling interrupts
|
|
||||||
|
|
||||||
if (port == NOT_A_PORT)
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
port -= 2; // from port (PB, PC, PD) to index in our array
|
|
||||||
pcmask = port_to_pcmask[port]; // point to PCMSK0 or 1 or 2 depending on the port corresponding to the pin
|
|
||||||
*pcmask |= bitM; // set the pin change interrupt mask through a pointer to PCMSK0 or 1 or 2
|
|
||||||
PCICR |= 0x01 << port; // enable the interrupt
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* Remove a pin to be handled */
|
|
||||||
byte RemovePinChangeInterrupt(uint8_t aPin) {
|
|
||||||
volatile uint8_t *pcmask;
|
|
||||||
|
|
||||||
uint8_t bitM = digitalPinToBitMask(aPin);
|
|
||||||
uint8_t port = digitalPinToPort(aPin);
|
|
||||||
|
|
||||||
if (port == NOT_A_PORT)
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
port -= 2; // from port (PB, PC, PD) to index in our array
|
|
||||||
pcmask = port_to_pcmask[port];
|
|
||||||
*pcmask &= ~bitM; // clear the bit in the mask.
|
|
||||||
if (*pcmask == 0) { // if that's the last one, disable the interrupt.
|
|
||||||
PCICR &= ~(0x01 << port);
|
|
||||||
}
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void PrintErrorMsg() {
|
|
||||||
int len = strlen_P(errorStr);
|
|
||||||
char myChar;
|
|
||||||
for (unsigned char k = 0; k < len; k++) {
|
|
||||||
myChar = pgm_read_byte_near(errorStr + k);
|
|
||||||
Serial.print(myChar);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void printVersion() {
|
|
||||||
int len = strlen_P(versionStr);
|
|
||||||
char myChar;
|
|
||||||
for (unsigned char k = 0; k < len; k++) {
|
|
||||||
myChar = pgm_read_byte_near(versionStr + k);
|
|
||||||
Serial.print(myChar);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
common interrupt handler. "port" is the PCINT port index (0-2), not PB, PC or PD which are mapped to 2-4
|
|
||||||
|
|
||||||
do counting and set start / end time of interval.
|
|
||||||
reporting is not triggered from here.
|
|
||||||
|
|
||||||
only here counter[] is modified
|
|
||||||
intervalEnd[] is set here and in report
|
|
||||||
intervalStart[] is set in case a pin was not initialized yet and in report
|
|
||||||
*/
|
|
||||||
static void PCint(uint8_t port) {
|
|
||||||
uint8_t bit;
|
|
||||||
uint8_t curr;
|
|
||||||
uint8_t delta;
|
|
||||||
uint8_t level;
|
|
||||||
uint8_t pulseLevel;
|
|
||||||
uint8_t pcintPin;
|
|
||||||
unsigned long len;
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
// get the pin states for the indicated port.
|
|
||||||
curr = *portInputRegister(port+2); // current pin states at port (add 2 to get from index to PB, PC or PD)
|
|
||||||
delta = curr ^ PCintLast[port]; // xor gets bits that are different
|
|
||||||
PCintLast[port] = curr; // store new pin state for next interrupt
|
|
||||||
|
|
||||||
if ((delta &= *port_to_pcmask[port]) == 0) // delta is pins that have changed. screen out non pcint pins.
|
|
||||||
return; /* no handled pin changed */
|
|
||||||
|
|
||||||
for (uint8_t i=0; i < 8; i++) { // loop over each pin on the given port that changed
|
|
||||||
bit = 0x01 << i;
|
|
||||||
if (delta & bit) { // did this pin change?
|
|
||||||
pcintPin = port * 8 + i; // pcint pin numbers follow the bits, only arduino pin nums are special
|
|
||||||
level = ((curr & bit) > 0);
|
|
||||||
pulseLevel = (pulseWidthStart[pcintPin] == RISING); // RISING means that pulse is at high level
|
|
||||||
|
|
||||||
len = now - lastChange[pcintPin];
|
|
||||||
histIndex++;
|
|
||||||
if (histIndex >= MAX_HIST) histIndex = 0;
|
|
||||||
histPin[histIndex] = pcintPin;
|
|
||||||
histTime[histIndex] = lastChange[pcintPin];
|
|
||||||
histLen[histIndex] = len;
|
|
||||||
histLevel[histIndex] = !level; // before it changed
|
|
||||||
histAct[histIndex] = ' ';
|
|
||||||
//histI1[histIndex] = lastLevel[pcintPin];
|
|
||||||
|
|
||||||
// go on if mode is CHANGE, or if RISING and bit is high, or if mode is FALLING and bit is low.
|
|
||||||
if (PCintMode[pcintPin] == CHANGE || level == pulseLevel) {
|
|
||||||
|
|
||||||
if (pulseWidthMin[pcintPin]) { // if minimal pulse length defined then check minimal pulse length and gap
|
|
||||||
|
|
||||||
if (len < pulseWidthMin[pcintPin]) {
|
|
||||||
lastChange[pcintPin] = now;
|
|
||||||
if (level != pulseLevel) { // if change to gap level
|
|
||||||
rejectCounter[pcintPin]++; // pulse too short
|
|
||||||
histAct[histIndex] = 'R';
|
|
||||||
} else {
|
|
||||||
histAct[histIndex] = 'X';
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
|
|
||||||
if (level == pulseLevel) { // edge does fit defined start, level is now pulse
|
|
||||||
// potential end of a valid gap, now we are at pulse level
|
|
||||||
if (lastLevel[pcintPin] == pulseLevel) { // last remembered valid level was also pulse
|
|
||||||
// last remembered valid level was pulse, now the gap was confirmed.
|
|
||||||
histAct[histIndex] = 'G';
|
|
||||||
} else {
|
|
||||||
// last remembered valid level was a gap -> now we had another valid gap -> inbetween was only a spike -> ignore
|
|
||||||
histAct[histIndex] = 'G';
|
|
||||||
}
|
|
||||||
|
|
||||||
} else { // edge is a change to gap, level is now gap
|
|
||||||
// potential end of a valid pulse, now we are at gap level
|
|
||||||
if (lastLevel[pcintPin] != pulseLevel) { // last remembered valid level was also gap
|
|
||||||
// last remembered valid level was a gap -> now we had valid new pulse -> count
|
|
||||||
|
|
||||||
intervalEnd[pcintPin] = now; // remember time of in case pulse will be the last in the interval
|
|
||||||
if (!firstPulse[pcintPin]) firstPulse[pcintPin] = now; // time of first impulse in this reporting interval
|
|
||||||
if (initialized[pcintPin]) {
|
|
||||||
counter[pcintPin]++; // count
|
|
||||||
} else {
|
|
||||||
counter[pcintPin]++; // count
|
|
||||||
counterIgn[pcintPin]++; // count as to be ignored for diff because it defines the start of the interval
|
|
||||||
intervalStart[pcintPin] = now; // if this is the very first impulse on this pin -> start interval now
|
|
||||||
initialized[pcintPin] = true; // and start counting the next impulse (so far counter is 0)
|
|
||||||
}
|
|
||||||
pulseWidthSum[pcintPin] += len; // for average calculation
|
|
||||||
histAct[histIndex] = 'C';
|
|
||||||
} else {
|
|
||||||
// last remembered valid level was a pulse -> now we had another valid pulse
|
|
||||||
// inbetween was an invalid drop so pulse is already counted.
|
|
||||||
pulseWidthSum[pcintPin] += len; // for average calculation
|
|
||||||
histAct[histIndex] = 'P';
|
|
||||||
}
|
|
||||||
} // change to gap level
|
|
||||||
|
|
||||||
// remember this valid level as lastLevel
|
|
||||||
lastLevel[pcintPin] = !level; // before it changed
|
|
||||||
|
|
||||||
} // if pulse is not too short
|
|
||||||
|
|
||||||
} // if pulseWidth checking
|
|
||||||
}
|
|
||||||
lastChange[pcintPin] = now;
|
|
||||||
} // if bit changed
|
|
||||||
} // for
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* show pulse history ring */
|
|
||||||
void showHistory() {
|
|
||||||
uint8_t hi;
|
|
||||||
Serial.println (F("D pulse history: "));
|
|
||||||
unsigned long now = millis();
|
|
||||||
unsigned long last;
|
|
||||||
uint8_t start = (histIndex + 2) % MAX_HIST;
|
|
||||||
for (uint8_t i = 0; i < MAX_HIST; i++) {
|
|
||||||
hi = (start + i) % MAX_HIST;
|
|
||||||
if (i == 0 || (last <= histTime[hi]+histLen[hi])) {
|
|
||||||
Serial.print (F("D pin "));
|
|
||||||
Serial.print (PCintActivePin[histPin[hi]]);
|
|
||||||
Serial.print (F(" start "));
|
|
||||||
Serial.print ((long) (histTime[hi] - now));
|
|
||||||
Serial.print (F(" len "));
|
|
||||||
Serial.print (histLen[hi]);
|
|
||||||
Serial.print (F(" at "));
|
|
||||||
Serial.print (histLevel[hi]);
|
|
||||||
Serial.print (F(" "));
|
|
||||||
Serial.print (histAct[hi]);
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
last = histTime[hi];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
report count and time for pins that are between min and max interval
|
|
||||||
|
|
||||||
lastCount[] is only modified here (count at time of last reporting)
|
|
||||||
intervalEnd[] is modified here and in ISR - disable interrupts in critcal moments to avoid garbage in var
|
|
||||||
intervalStart[] is modified only here (or for very first Interrupt in ISR) -> no problem.
|
|
||||||
*/
|
|
||||||
void report() {
|
|
||||||
int aPin;
|
|
||||||
unsigned long count, countIgn, countDiff, realDiff;
|
|
||||||
unsigned long timeDiff, now;
|
|
||||||
unsigned long startT, endT;
|
|
||||||
unsigned long avgLen;
|
|
||||||
now = millis();
|
|
||||||
|
|
||||||
for (int pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++) { // go through all observed pins as PCINT pin number
|
|
||||||
aPin = PCintActivePin[pcintPin]; // take saved arduino pin number
|
|
||||||
if (aPin < 1) continue; // 0 means pin is not active for reporting
|
|
||||||
noInterrupts();
|
|
||||||
startT = intervalStart[pcintPin];
|
|
||||||
endT = intervalEnd[pcintPin];
|
|
||||||
count = counter[pcintPin]; // get current counter (counts all pulses
|
|
||||||
countIgn = counterIgn[pcintPin]; // pulses that mark the beginning of an interval and should not be taken into calculation (happens after restart)
|
|
||||||
interrupts();
|
|
||||||
|
|
||||||
timeDiff = endT - startT; // time between first and last impulse during interval
|
|
||||||
countDiff = count - countIgn - lastCount[pcintPin]; // how many pulses during intervall since last report? (ignore forst pulse after device restart)
|
|
||||||
realDiff = count - lastCount[pcintPin]; // (works with wrapping)
|
|
||||||
if((long)(now - (lastReport[pcintPin] + intervalMax)) >= 0) { // intervalMax is over
|
|
||||||
if ((countDiff >= countMin) && (timeDiff > intervalSml) && (intervalMin != intervalMax)) {
|
|
||||||
// normal procedure
|
|
||||||
lastCount[pcintPin] = count; // remember current count for next interval
|
|
||||||
noInterrupts();
|
|
||||||
intervalStart[pcintPin] = endT; // time of last impulse in this interval becomes also time of first impulse in next
|
|
||||||
counterIgn[pcintPin] = 0;
|
|
||||||
interrupts();
|
|
||||||
} else {
|
|
||||||
// nothing counted or counts happened during a fraction of intervalMin only
|
|
||||||
noInterrupts();
|
|
||||||
intervalEnd[pcintPin] = now; // don't calculate with last impulse, use now instead
|
|
||||||
intervalStart[pcintPin] = now; // start a new interval for next report now
|
|
||||||
counterIgn[pcintPin] = 0;
|
|
||||||
interrupts();
|
|
||||||
lastCount[pcintPin] = count; // remember current count for next interval
|
|
||||||
timeDiff = now - startT; // special handling - calculation ends now instead of last impulse
|
|
||||||
}
|
|
||||||
} else if((long)(now - (lastReport[pcintPin] + intervalMin)) >= 0) { // minInterval has elapsed
|
|
||||||
if ((countDiff >= countMin) && (timeDiff > intervalSml)) {
|
|
||||||
// normal procedure
|
|
||||||
lastCount[pcintPin] = count; // remember current count for next interval
|
|
||||||
noInterrupts();
|
|
||||||
intervalStart[pcintPin] = endT; // time of last impulse in this interval becomes also time of first impulse in next
|
|
||||||
counterIgn[pcintPin] = 0;
|
|
||||||
interrupts();
|
|
||||||
} else continue; // not enough counted - wait
|
|
||||||
} else continue; // intervalMin not over - wait
|
|
||||||
|
|
||||||
Serial.print(F("R")); // R Report
|
|
||||||
Serial.print(aPin);
|
|
||||||
Serial.print(F(" C")); // C - Count
|
|
||||||
Serial.print(count);
|
|
||||||
Serial.print(F(" D")); // D - Count Diff (without pulse that marks the begin of an interval)
|
|
||||||
Serial.print(countDiff);
|
|
||||||
Serial.print(F(" R")); // R - real Diff for incrementing long counter in Fhem - includes even the first pulse after restart
|
|
||||||
Serial.print(realDiff);
|
|
||||||
Serial.print(F(" T")); // T - Time
|
|
||||||
Serial.print(timeDiff);
|
|
||||||
Serial.print(F(" N")); // N - now
|
|
||||||
Serial.print((long)now);
|
|
||||||
|
|
||||||
// rejected count ausgeben
|
|
||||||
// evt auch noch average pulse len und gap len
|
|
||||||
if (pulseWidthMin[pcintPin]) { // check minimal pulse length and gap
|
|
||||||
Serial.print(F(" X")); // X Reject
|
|
||||||
Serial.print(rejectCounter[pcintPin] - lastRejCount[pcintPin]);
|
|
||||||
noInterrupts();
|
|
||||||
lastRejCount[pcintPin] = rejectCounter[pcintPin];
|
|
||||||
interrupts();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (realDiff) {
|
|
||||||
Serial.print(F(" F")); // F - first impulse after the one that started the interval
|
|
||||||
Serial.print((long)firstPulse[pcintPin] - startT);
|
|
||||||
Serial.print(F(" L")); // L - last impulse - marking the end of this interval
|
|
||||||
Serial.print((long)endT - startT);
|
|
||||||
firstPulse[pcintPin] = 0;
|
|
||||||
|
|
||||||
if (pulseWidthMin[pcintPin]) {// check minimal pulse length and gap
|
|
||||||
noInterrupts();
|
|
||||||
avgLen = pulseWidthSum[pcintPin] / countDiff;
|
|
||||||
pulseWidthSum[pcintPin] = 0;
|
|
||||||
interrupts();
|
|
||||||
Serial.print(F(" A"));
|
|
||||||
Serial.print(avgLen);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t hi;
|
|
||||||
boolean first = true;
|
|
||||||
uint8_t start = (histIndex + 2) % MAX_HIST;
|
|
||||||
unsigned long last;
|
|
||||||
Serial.print (F(" H"));
|
|
||||||
for (uint8_t i = 0; i < MAX_HIST; i++) {
|
|
||||||
hi = (start + i) % MAX_HIST;
|
|
||||||
if (histPin[hi] == pcintPin) {
|
|
||||||
if (first || (last <= histTime[hi]+histLen[hi])) {
|
|
||||||
if (!first)
|
|
||||||
Serial.print (F(", "));
|
|
||||||
//Serial.print (F(""));
|
|
||||||
Serial.print ((long) (histTime[hi] - now));
|
|
||||||
Serial.print (F("/"));
|
|
||||||
Serial.print (histLen[hi]);
|
|
||||||
Serial.print (F(":"));
|
|
||||||
Serial.print (histLevel[hi]);
|
|
||||||
//Serial.print (F(" "));
|
|
||||||
Serial.print (histAct[hi]);
|
|
||||||
first = false;
|
|
||||||
}
|
|
||||||
last = histTime[hi];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
Serial.println();
|
|
||||||
lastReport[pcintPin] = now; // remember when we reported
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* print status for one pin */
|
|
||||||
void showPin(byte pcintPin) {
|
|
||||||
unsigned long newCount, countIgn, countDiff;
|
|
||||||
unsigned long timeDiff;
|
|
||||||
unsigned long avgLen;
|
|
||||||
|
|
||||||
timeDiff = intervalEnd[pcintPin] - intervalStart[pcintPin];
|
|
||||||
newCount = counter[pcintPin];
|
|
||||||
countIgn = counterIgn[pcintPin];
|
|
||||||
countDiff = newCount - countIgn - lastCount[pcintPin];
|
|
||||||
if (!timeDiff)
|
|
||||||
timeDiff = millis() - intervalStart[pcintPin];
|
|
||||||
|
|
||||||
Serial.print(F("PCInt pin "));
|
|
||||||
Serial.print(pcintPin);
|
|
||||||
|
|
||||||
Serial.print(F(", iMode "));
|
|
||||||
switch (PCintMode[pcintPin]) {
|
|
||||||
case RISING: Serial.print(F("rising")); break;
|
|
||||||
case FALLING: Serial.print(F("falling")); break;
|
|
||||||
case CHANGE: Serial.print(F("change")); break;
|
|
||||||
}
|
|
||||||
if (pulseWidthMin[pcintPin] > 0) {
|
|
||||||
Serial.print(F(", min len "));
|
|
||||||
Serial.print(pulseWidthMin[pcintPin]);
|
|
||||||
Serial.print(F(" ms"));
|
|
||||||
switch (pulseWidthStart[pcintPin]) {
|
|
||||||
case RISING: Serial.print(F(" rising")); break;
|
|
||||||
case FALLING: Serial.print(F(" falling")); break;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
Serial.print(F(", no min len"));
|
|
||||||
}
|
|
||||||
Serial.print(F(", count "));
|
|
||||||
Serial.print(newCount);
|
|
||||||
Serial.print(F(" (+"));
|
|
||||||
Serial.print(countDiff);
|
|
||||||
Serial.print(F(") in "));
|
|
||||||
Serial.print(timeDiff);
|
|
||||||
Serial.print(F(" ms"));
|
|
||||||
|
|
||||||
// rejected count ausgeben
|
|
||||||
// evt auch noch average pulse len und gap len
|
|
||||||
if (pulseWidthMin[pcintPin]) { // check minimal pulse length and gap
|
|
||||||
Serial.print(F(" Rej "));
|
|
||||||
Serial.print(rejectCounter[pcintPin] - lastRejCount[pcintPin]);
|
|
||||||
}
|
|
||||||
if (countDiff) {
|
|
||||||
Serial.println();
|
|
||||||
Serial.print(F("M first at "));
|
|
||||||
Serial.print((long)firstPulse[pcintPin] - lastReport[pcintPin]);
|
|
||||||
Serial.print(F(", last at "));
|
|
||||||
Serial.print((long)intervalEnd[pcintPin] - lastReport[pcintPin]);
|
|
||||||
noInterrupts();
|
|
||||||
avgLen = pulseWidthSum[pcintPin] / countDiff;
|
|
||||||
interrupts();
|
|
||||||
Serial.print(F(", avg len "));
|
|
||||||
Serial.print(avgLen);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* give status report in between if requested over serial input */
|
|
||||||
void showCmd() {
|
|
||||||
Serial.print(F("M Status: "));
|
|
||||||
printVersion();
|
|
||||||
Serial.println();
|
|
||||||
Serial.print(F("M normal interval "));
|
|
||||||
Serial.println(intervalMin);
|
|
||||||
Serial.print(F("M max interval "));
|
|
||||||
Serial.println(intervalMax);
|
|
||||||
Serial.print(F("M min interval "));
|
|
||||||
Serial.println(intervalSml);
|
|
||||||
Serial.print(F("M min count "));
|
|
||||||
Serial.println(countMin);
|
|
||||||
|
|
||||||
for (byte pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++) {
|
|
||||||
int aPin = PCintActivePin[pcintPin];
|
|
||||||
if (aPin > 0) {
|
|
||||||
Serial.print(F("M pin "));
|
|
||||||
Serial.print(aPin);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
showPin(pcintPin);
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Serial.print(F("M Next report in "));
|
|
||||||
Serial.print(timeNextReport - millis());
|
|
||||||
Serial.print(F(" Milliseconds"));
|
|
||||||
Serial.println();
|
|
||||||
showHistory();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
handle add command.
|
|
||||||
todo: check size and clear options not passed
|
|
||||||
*/
|
|
||||||
void addCmd(unsigned int *values, byte size) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (used as index for most arrays)
|
|
||||||
byte mode = 2;
|
|
||||||
uint8_t port;
|
|
||||||
unsigned int pw;
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
|
|
||||||
//Serial.println(F("M Add called"));
|
|
||||||
int aPin = values[0]; // value 0 is pin number
|
|
||||||
pcintPin = digitalPinToPcIntPin(aPin);
|
|
||||||
if (aPin >= MAX_ARDUINO_PIN || aPin < 1
|
|
||||||
|| allowedPins[aPin] == 0 || pcintPin > MAX_PCINT_PIN) {
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("Illegal pin specification "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
return;
|
|
||||||
};
|
|
||||||
port = digitalPinToPort(aPin) - 2;
|
|
||||||
|
|
||||||
switch (values[1]) { // value 1 is rising / falling etc.
|
|
||||||
case 2:
|
|
||||||
mode = FALLING;
|
|
||||||
pulseWidthStart[pcintPin] = FALLING;
|
|
||||||
break;
|
|
||||||
case 3:
|
|
||||||
mode = RISING;
|
|
||||||
pulseWidthStart[pcintPin] = RISING;
|
|
||||||
break;
|
|
||||||
case 1:
|
|
||||||
mode = CHANGE;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("Illegal mode for pin specification "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
}
|
|
||||||
|
|
||||||
pinMode (aPin, INPUT);
|
|
||||||
if (size > 2 && values[2]) { // value 2 is pullup
|
|
||||||
digitalWrite (aPin, HIGH); // enable pullup resistor
|
|
||||||
}
|
|
||||||
|
|
||||||
if (size > 3 && values[3] > 0) { // value 3 is min length (if given)
|
|
||||||
pw = values[3];
|
|
||||||
mode = CHANGE;
|
|
||||||
} else {
|
|
||||||
pw = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!AddPinChangeInterrupt(aPin)) { // add Pin Change Interrupt
|
|
||||||
PrintErrorMsg(); Serial.println(F("AddInt"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
PCintMode[pcintPin] = mode; // save mode for ISR which uses the pcintPin as index
|
|
||||||
|
|
||||||
pulseWidthMin[pcintPin] = pw; // minimal pulse width in millis, 0 if not specified in add cmd todo: needs fixing! values[3] might contain data from last command
|
|
||||||
|
|
||||||
if (PCintActivePin[pcintPin] != aPin) { // in case this pin is not already active counting
|
|
||||||
PCintLast[port] = *portInputRegister(port+2); // current pin states at port
|
|
||||||
PCintActivePin[pcintPin] = aPin; // save real arduino pin number and flag this pin as active for reporting
|
|
||||||
initialized[pcintPin] = false; // initialize arrays for this pin
|
|
||||||
counter[pcintPin] = 0;
|
|
||||||
counterIgn[pcintPin] = 0;
|
|
||||||
lastCount[pcintPin] = 0;
|
|
||||||
intervalStart[pcintPin] = now;
|
|
||||||
intervalEnd[pcintPin] = now;
|
|
||||||
lastReport[pcintPin] = now; // next reporting cycle is probably earlier than now+intervalMin (already started) so report will be later than next interval
|
|
||||||
lastChange[pcintPin] = now;
|
|
||||||
rejectCounter[pcintPin] = 0;
|
|
||||||
lastRejCount[pcintPin] = 0;
|
|
||||||
}
|
|
||||||
Serial.print(F("M defined pin "));
|
|
||||||
Serial.print(aPin);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
showPin(pcintPin);
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
handle rem command.
|
|
||||||
*/
|
|
||||||
void removeCmd(unsigned int *values, byte size) {
|
|
||||||
uint8_t pcintPin; // PCINT pin number for the pin to be added (used as index for most arrays)
|
|
||||||
int aPin = values[0];
|
|
||||||
pcintPin = digitalPinToPcIntPin(aPin);
|
|
||||||
if (size < 1 || aPin >= MAX_ARDUINO_PIN || aPin < 1
|
|
||||||
|| allowedPins[aPin] == 0 || pcintPin > MAX_PCINT_PIN) {
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("Illegal pin specification "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
return;
|
|
||||||
};
|
|
||||||
|
|
||||||
if (!RemovePinChangeInterrupt(aPin)) {
|
|
||||||
PrintErrorMsg(); Serial.println(F("RemInt"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
PCintActivePin[pcintPin] = 0;
|
|
||||||
initialized[pcintPin] = false; // reset for next add
|
|
||||||
counter[pcintPin] = 0;
|
|
||||||
counterIgn[pcintPin] = 0;
|
|
||||||
lastCount[pcintPin] = 0;
|
|
||||||
pulseWidthMin[pcintPin] = 0;
|
|
||||||
lastRejCount[pcintPin] = 0;
|
|
||||||
rejectCounter[pcintPin] = 0;
|
|
||||||
|
|
||||||
Serial.print(F("M removed "));
|
|
||||||
Serial.println(aPin);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void intervalCmd(unsigned int *values, byte size) {
|
|
||||||
if (size < 4) { // i command always gets 4 values: min, max, sml, cntMin
|
|
||||||
PrintErrorMsg();
|
|
||||||
Serial.print(F("size"));
|
|
||||||
Serial.println();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
if (values[0] < 1 || values[0] > 3600) {
|
|
||||||
PrintErrorMsg(); Serial.println(values[0]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
intervalMin = (long)values[0] * 1000;
|
|
||||||
if (millis() + intervalMin < timeNextReport)
|
|
||||||
timeNextReport = millis() + intervalMin;
|
|
||||||
|
|
||||||
if (values[1] < 1 || values[1] > 3600) {
|
|
||||||
PrintErrorMsg(); Serial.println(values[1]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
intervalMax = (long)values[1]* 1000;
|
|
||||||
|
|
||||||
if (values[2] > 3600) {
|
|
||||||
PrintErrorMsg(); Serial.println(values[2]);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
intervalSml = (long)values[2] * 1000;
|
|
||||||
countMin = values[3];
|
|
||||||
|
|
||||||
Serial.print(F("M intervals set to "));
|
|
||||||
Serial.print(values[0]);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
Serial.print(values[1]);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
Serial.print(values[2]);
|
|
||||||
Serial.print(F(" "));
|
|
||||||
Serial.print(values[3]);
|
|
||||||
Serial.println();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void helloCmd() {
|
|
||||||
Serial.println();
|
|
||||||
printVersion();
|
|
||||||
Serial.println(F("Hello"));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static void HandleSerialPort(char c) {
|
|
||||||
static unsigned int value;
|
|
||||||
|
|
||||||
if (c == ',') {
|
|
||||||
if (commandDataPointer < (MAX_INPUT_NUM - 1)) {
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
commandDataPointer++;
|
|
||||||
value = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if ('0' <= c && c <= '9') {
|
|
||||||
value = 10 * value + c - '0';
|
|
||||||
}
|
|
||||||
else if ('a' <= c && c <= 'z') {
|
|
||||||
switch (c) {
|
|
||||||
case 'a':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
addCmd(commandData, ++commandDataPointer);
|
|
||||||
break;
|
|
||||||
case 'd':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
removeCmd(commandData, ++commandDataPointer);
|
|
||||||
break;
|
|
||||||
case 'i':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
intervalCmd(commandData, ++commandDataPointer);
|
|
||||||
break;
|
|
||||||
case 'r':
|
|
||||||
initialize();
|
|
||||||
break;
|
|
||||||
case 's':
|
|
||||||
showCmd();
|
|
||||||
break;
|
|
||||||
case 'h':
|
|
||||||
helloCmd();
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
//PrintErrorMsg(); Serial.println();
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
commandDataPointer = 0;
|
|
||||||
value = 0;
|
|
||||||
for (byte i=0; i < MAX_INPUT_NUM; i++)
|
|
||||||
commandData[i] = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
SIGNAL(PCINT0_vect) {
|
|
||||||
PCint(0);
|
|
||||||
}
|
|
||||||
SIGNAL(PCINT1_vect) {
|
|
||||||
PCint(1);
|
|
||||||
}
|
|
||||||
SIGNAL(PCINT2_vect) {
|
|
||||||
PCint(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void initialize() {
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
Serial.println();
|
|
||||||
printVersion();
|
|
||||||
Serial.println(F(" Started"));
|
|
||||||
|
|
||||||
for (int pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++) {
|
|
||||||
PCintActivePin[pcintPin] = 0; // set all pins to inactive (0)
|
|
||||||
initialized[pcintPin] = false; // initialize arrays for this pin
|
|
||||||
counter[pcintPin] = 0;
|
|
||||||
counterIgn[pcintPin] = 0;
|
|
||||||
lastCount[pcintPin] = 0;
|
|
||||||
intervalStart[pcintPin] = now;
|
|
||||||
intervalEnd[pcintPin] = now;
|
|
||||||
lastChange[pcintPin] = now;
|
|
||||||
pulseWidthMin[pcintPin] = 0;
|
|
||||||
rejectCounter[pcintPin] = 0;
|
|
||||||
lastRejCount[pcintPin] = 0;
|
|
||||||
lastReport[pcintPin] = now;
|
|
||||||
}
|
|
||||||
|
|
||||||
for (unsigned int port=0; port <= 2; port++) {
|
|
||||||
PCintLast[port] = *portInputRegister(port+2); // current pin states at port
|
|
||||||
}
|
|
||||||
|
|
||||||
timeNextReport = millis() + intervalMin; // time for first output
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void setup() {
|
|
||||||
Serial.begin(SERIAL_SPEED); // initialize serial
|
|
||||||
delay (500);
|
|
||||||
interrupts();
|
|
||||||
initialize();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
Main Loop
|
|
||||||
checks if report should be called because timeNextReport is reached
|
|
||||||
or lastReport for one pin is older than intervalMax
|
|
||||||
timeNextReport is only set here (and when interval is changed / at setup)
|
|
||||||
*/
|
|
||||||
void loop() {
|
|
||||||
unsigned long now = millis();
|
|
||||||
|
|
||||||
if (Serial.available()) {
|
|
||||||
HandleSerialPort(Serial.read());
|
|
||||||
}
|
|
||||||
boolean doReport = false; // check if report nedds to be called
|
|
||||||
if((long)(now - timeNextReport) >= 0) // works fine when millis wraps.
|
|
||||||
doReport = true; // intervalMin is over
|
|
||||||
else
|
|
||||||
for (byte pcintPin=0; pcintPin < MAX_PCINT_PIN; pcintPin++)
|
|
||||||
if (PCintActivePin[pcintPin] > 0)
|
|
||||||
if((long)(now - (lastReport[pcintPin] + intervalMax)) >= 0)
|
|
||||||
doReport = true; // active pin has not been reported for langer than intervalMax
|
|
||||||
|
|
||||||
if (doReport) {
|
|
||||||
report();
|
|
||||||
timeNextReport = now + intervalMin; // do it again after intervalMin millis
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
@ -24,6 +24,16 @@
|
|||||||
* A0-A5 (D14-D19) = PCINT 8-13 = PCIR1 = PC = PCIE1 = pcmsk1
|
* A0-A5 (D14-D19) = PCINT 8-13 = PCIR1 = PC = PCIE1 = pcmsk1
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/* test cmds analog ESP:
|
||||||
|
* 20v Verbose
|
||||||
|
* 17,3,0,50a A0, rising, no Pullup, MinLen 50
|
||||||
|
* 15,25t Level Diff Thresholds
|
||||||
|
*
|
||||||
|
* for ESP with D5 falling pullup 30
|
||||||
|
* 5,2,1,30a
|
||||||
|
* 20v
|
||||||
|
* 10,20,1,1i
|
||||||
|
*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Changes:
|
Changes:
|
||||||
@ -72,26 +82,39 @@
|
|||||||
7.3.18 - change pin config output, fix pullup (V2.26), store config in eeprom and read it back after boot
|
7.3.18 - change pin config output, fix pullup (V2.26), store config in eeprom and read it back after boot
|
||||||
22.4.18 - many changes, delay report if tcp mode and disconnected, verbose levels, ...
|
22.4.18 - many changes, delay report if tcp mode and disconnected, verbose levels, ...
|
||||||
13.5.18 - V2.36 Keepalive also on Arduino side
|
13.5.18 - V2.36 Keepalive also on Arduino side
|
||||||
|
9.12.18 - V3.0 start implementing analog input for old ferraris counters
|
||||||
|
6.1.19 - V3.1 showIntervals in hello
|
||||||
|
19.1.19 - V3.12 support for ESP with analog
|
||||||
|
24.2.19 - V3.13 fix internal pin to GPIO mapping (must match ISR functions) when ESP8266 and analog support
|
||||||
|
- V3.14 added return of devVerbose upon startup
|
||||||
|
27.6.19 - V3.20 replace timeNextReport with lastReportCall to avoid problem with data tyoes on ESP
|
||||||
|
fix a bug with analog counting on the ESP
|
||||||
|
|
||||||
ToDo / Ideas:
|
ToDo / Ideas:
|
||||||
|
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/* Remove this before compiling */
|
||||||
|
/* #define TestConfig */
|
||||||
|
|
||||||
|
|
||||||
/* allow printing of every pin change to Serial */
|
/* allow printing of every pin change to Serial */
|
||||||
#define debugPins 1
|
#define debugPins 1
|
||||||
|
|
||||||
/* allow tracking of pulse lengths */
|
/* allow tracking of pulse lengths */
|
||||||
#define pulseHistory 1
|
#define pulseHistory 1
|
||||||
|
|
||||||
|
/* support analog input for ferraris counters with IR light hardware */
|
||||||
|
#define analogIR 1
|
||||||
|
|
||||||
/* use a sample config at boot */
|
/* use a sample config at boot */
|
||||||
// #define debugCfg 1
|
// #define debugCfg 1
|
||||||
|
|
||||||
#include "pins_arduino.h"
|
#include "pins_arduino.h"
|
||||||
#include <EEPROM.h>
|
#include <EEPROM.h>
|
||||||
|
|
||||||
const char versionStr[] PROGMEM = "ArduCounter V2.36";
|
const char versionStr[] PROGMEM = "ArduCounter V3.20";
|
||||||
const char compile_date[] PROGMEM = __DATE__ " " __TIME__;
|
const char compile_date[] PROGMEM = __DATE__ " " __TIME__;
|
||||||
const char errorStr[] PROGMEM = "Error: ";
|
const char errorStr[] PROGMEM = "Error: ";
|
||||||
|
|
||||||
@ -100,7 +123,11 @@ const char boardName1[] PROGMEM = ARDUINO_BOARD;
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__)
|
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__)
|
||||||
|
#ifdef ARDUINO_AVR_NANO
|
||||||
|
const char boardName[] PROGMEM = "NANO";
|
||||||
|
#else
|
||||||
const char boardName[] PROGMEM = "UNO";
|
const char boardName[] PROGMEM = "UNO";
|
||||||
|
#endif
|
||||||
#elif defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega16U4__)
|
#elif defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega16U4__)
|
||||||
const char boardName[] PROGMEM = "Leonardo";
|
const char boardName[] PROGMEM = "Leonardo";
|
||||||
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||||
@ -113,15 +140,29 @@ const char boardName[] PROGMEM = "UNKNOWN";
|
|||||||
|
|
||||||
#define SERIAL_SPEED 38400
|
#define SERIAL_SPEED 38400
|
||||||
#define MAX_INPUT_NUM 8
|
#define MAX_INPUT_NUM 8
|
||||||
#define MAX_HIST 20
|
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
int sensorValueOff = 0; // value read from the photo transistor when ir LED is off
|
||||||
|
int sensorValueOn = 0; // value read from the photo transistor when ir LED is on
|
||||||
|
int analogThresholdMin = 100; // min value of analog input
|
||||||
|
int analogThresholdMax = 110; // max value of analog input
|
||||||
|
|
||||||
#ifdef ESP8266
|
uint8_t triggerState; // todo: use existing arrays instead
|
||||||
// varibales / definitions for ESP 8266 based boards
|
|
||||||
#include <ESP8266WiFi.h>
|
|
||||||
|
|
||||||
|
// save measurement during same level as sum and count to get average and then put in history when doCount is called
|
||||||
|
// but how do we do this before we can detect the levels?
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ESP8266 // ESP variables and definitions
|
||||||
|
#include <ESP8266WiFi.h> // =============================
|
||||||
|
|
||||||
|
#ifdef TestConfig
|
||||||
|
#include "ArduCounterTestConfig.h"
|
||||||
|
#else
|
||||||
const char* ssid = "MySSID";
|
const char* ssid = "MySSID";
|
||||||
const char* password = "secret";
|
const char* password = "secret";
|
||||||
|
#endif
|
||||||
|
|
||||||
WiFiServer Server(80); // For ESP WiFi connection
|
WiFiServer Server(80); // For ESP WiFi connection
|
||||||
WiFiClient Client1; // active TCP connection
|
WiFiClient Client1; // active TCP connection
|
||||||
@ -133,6 +174,47 @@ boolean tcpMode = false;
|
|||||||
uint8_t delayedTcpReports = 0; // how often did we already delay reporting because tcp disconnected
|
uint8_t delayedTcpReports = 0; // how often did we already delay reporting because tcp disconnected
|
||||||
uint32_t lastDelayedTcpReports = 0; // last time we delayed
|
uint32_t lastDelayedTcpReports = 0; // last time we delayed
|
||||||
|
|
||||||
|
#define MAX_HIST 20 // 20 history entries for ESP boards (can be increased)
|
||||||
|
|
||||||
|
#ifdef analogIR // code for ESP with analog pin and reflection light barrier support (test)
|
||||||
|
|
||||||
|
#define MAX_APIN 18
|
||||||
|
#define MAX_PIN 9
|
||||||
|
|
||||||
|
/* ESP8266 pins that are typically ok to use
|
||||||
|
* (some might be set to -1 (disallowed) because they are used
|
||||||
|
* as reset, serial, led or other things on most boards)
|
||||||
|
* maps printed pin numbers (aPin) to sketch internal index numbers */
|
||||||
|
short allowedPins[MAX_APIN] = // ESP 8266 with analog:
|
||||||
|
{ 0, 1, 2, -1, // printed pin numbers 0,1,2 are ok to be used
|
||||||
|
-1, 5, -1, -1, // printed pin number 5 is ok to be used
|
||||||
|
-1, -1, -1, -1, // 8-11 not avaliable
|
||||||
|
-1, -1, -1, -1, // 12-15 not avaliable
|
||||||
|
-1, 8 }; // 16 not available, 17 is analog
|
||||||
|
|
||||||
|
/* Wemos / NodeMCU Pins 3,4 and 8 (GPIO 0,2 and 15) define boot mode and therefore
|
||||||
|
* can not be used to connect to signal */
|
||||||
|
|
||||||
|
/* Map from sketch internal pin index to real chip IO pin number (not aPin, e.g. for ESP)
|
||||||
|
Note that the internal numbers might be different from the printed
|
||||||
|
pin numbers (e.g. pin 0 is in index 0 but real chip pin number 16! */
|
||||||
|
short internalPins[MAX_PIN] =
|
||||||
|
{ D0, D1, D2, D3, // map from internal pin Index to
|
||||||
|
D4, D5, D6, D7, // real GPIO pin numbers / defines
|
||||||
|
A0 }; // D0=16, D1=5, D2=4, D5=14, A0=17
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
uint8_t analogPins[MAX_PIN] =
|
||||||
|
{ 0,0,0,0,0,0,0,0,1 }; // ESP pin A0 (pinIndex 8, internal 17) is analog
|
||||||
|
|
||||||
|
const int analogInPin = A0; // Analog input pin that the photo transistor is attached to (internally number 17)
|
||||||
|
const int irOutPin = D6; // Digital output pin that the IR-LED is attached to
|
||||||
|
const int ledOutPin = D7; // Signal LED output pin
|
||||||
|
|
||||||
|
#else // code for ESP without analog pin and reflection light barrier support
|
||||||
|
|
||||||
|
|
||||||
#define MAX_APIN 8
|
#define MAX_APIN 8
|
||||||
#define MAX_PIN 8
|
#define MAX_PIN 8
|
||||||
|
|
||||||
@ -140,42 +222,99 @@ uint32_t lastDelayedTcpReports = 0; // last time we delayed
|
|||||||
* (some might be set to -1 (disallowed) because they are used
|
* (some might be set to -1 (disallowed) because they are used
|
||||||
* as reset, serial, led or other things on most boards)
|
* as reset, serial, led or other things on most boards)
|
||||||
* maps printed pin numbers to sketch internal index numbers */
|
* maps printed pin numbers to sketch internal index numbers */
|
||||||
short allowedPins[MAX_APIN] =
|
short allowedPins[MAX_APIN] = // ESP 8266 without analog:
|
||||||
{ 0, 1, 2, -1,
|
{ 0, 1, 2, -1, // printed pin numbers 0,1,2 are ok to be used, 3 not
|
||||||
-1, 5, 6, 7};
|
-1, 5, 6, 7}; // printed pin numbers 5-7 are ok to be used, 4 not, >8 not
|
||||||
|
|
||||||
/* Wemos / NodeMCU Pins 3,4 and 8 (GPIO 0,2 and 15) define boot mode and therefore
|
/* Wemos / NodeMCU Pins 3,4 and 8 (GPIO 0,2 and 15) define boot mode and therefore
|
||||||
* can not be used to connect to signal
|
* can not be used to connect to signal */
|
||||||
*/
|
|
||||||
|
|
||||||
/* Map from sketch internal pin index to real chip IO pin number */
|
/* Map from sketch internal pin index to real chip IO pin number (not aPin, e.g. for ESP)
|
||||||
|
Note that the internal numbers might be different from the printed
|
||||||
|
pin numbers (e.g. pin 0 is in index 0 but real chip pin number 16! */
|
||||||
short internalPins[MAX_PIN] =
|
short internalPins[MAX_PIN] =
|
||||||
{ 16, 5, 4, 0,
|
{ D0, D1, D2, D3, // printed pin numbers 0, 1, 2, 3 (3 should not be used and could be removed here)
|
||||||
2, 14, 12, 13};
|
D5, D5, D6, D7}; // printed pin numbers 4, 5, 6, 7 (4 should not be used and could be removed here)
|
||||||
|
// D0=16, D1=5, D2=4, D5=14, A0=17, ...
|
||||||
|
|
||||||
#else
|
#endif // end of ESP section without analog reading
|
||||||
// variables / definitions for arduino / 328p based boards
|
|
||||||
#define MAX_APIN 22
|
|
||||||
#define MAX_PIN 20
|
|
||||||
|
|
||||||
|
#else // Arduino Uno or Nano variables and definitions
|
||||||
|
// =============================================
|
||||||
|
|
||||||
|
#define MAX_HIST 20 // 20 history entries for arduino boards
|
||||||
|
|
||||||
/* arduino pins that are typically ok to use
|
/* arduino pins that are typically ok to use
|
||||||
* (some might be set to -1 (disallowed) because they are used
|
* (some might be set to -1 (disallowed) because they are used
|
||||||
* as reset, serial, led or other things on most boards)
|
* as reset, serial, led or other things on most boards)
|
||||||
* maps printed pin numbers to sketch internal index numbers */
|
* maps printed pin numbers to sketch internal index numbers */
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
|
||||||
|
/* 2 is used for IR out, 12 for signal, A7 for In */
|
||||||
|
#define MAX_APIN 22
|
||||||
|
#define MAX_PIN 18
|
||||||
|
|
||||||
short allowedPins[MAX_APIN] =
|
short allowedPins[MAX_APIN] =
|
||||||
{-1, -1, 0, 1,
|
{-1, -1, -1, 0, /* arduino pin 0 - 3 to internal index or -1 if pin is reserved */
|
||||||
2, 3, 4, 5,
|
1, 2, 3, 4, /* arduino pin 4 - 7 to internal index */
|
||||||
6, 7, 8, 9,
|
5, 6, 7, 8, /* arduino pin 8 - 11 to internal index */
|
||||||
10, 11, 12, 13,
|
-1, 9, 10, 11, /* arduino pin 12, 13, A0, A1 / 14, 15 to internal index or -1 if pin is reserved*/
|
||||||
14, 15, 16, 17,
|
12, 13, 14, 15, /* arduino pin A2 - A5 / 16 - 19 to internal index */
|
||||||
18, 19 };
|
16, 17 }; /* arduino pin A6, A7 to internal index */
|
||||||
|
|
||||||
/* Map from sketch internal pin index to real chip IO pin number */
|
/* Map from sketch internal pin index to real chip IO pin number */
|
||||||
short internalPins[MAX_PIN] =
|
short internalPins[MAX_PIN] =
|
||||||
{ 2, 3, 4, 5,
|
{ 3, 4, 5, 6, /* index 0 - 3 map to pins 3 - 6 */
|
||||||
6, 7, 8, 9,
|
7, 8, 9, 10, /* index 4 - 7 map to pins 7 - 10 */
|
||||||
10, 11, 12, 13,
|
11, 12, 14, 15, /* index 8 - 11 map to pins 11,13, A0 - A1 */
|
||||||
14, 15, 16, 17,
|
16, 17, 18, 19, /* index 12 - 15 map to pins A2 - A5 */
|
||||||
18, 19 };
|
20, 21 }; /* index 16 - 17 map to pin A6, A7 */
|
||||||
|
|
||||||
|
uint8_t analogPins[MAX_PIN] =
|
||||||
|
{ 0,0,0,0, /* everything except Arduino A7 (pinIndex 17, internal 21) is digital by default */
|
||||||
|
0,0,0,0,
|
||||||
|
0,0,0,0,
|
||||||
|
0,0,0,0,
|
||||||
|
0,1 };
|
||||||
|
|
||||||
|
const int analogInPin = A7; // Arduino analog input pin that the photo transistor is attached to (internal 21)
|
||||||
|
const int irOutPin = 2; // Digital output pin that the IR-LED is attached to
|
||||||
|
const int ledOutPin = 12; // Signal LED output pin
|
||||||
|
|
||||||
|
|
||||||
|
#else
|
||||||
|
/* no analog IR support -> all Nano pins including analog available für digital counting */
|
||||||
|
|
||||||
|
#define MAX_APIN 22
|
||||||
|
#define MAX_PIN 20
|
||||||
|
short allowedPins[MAX_APIN] =
|
||||||
|
{-1, -1, 0, 1, /* arduino pin 0 - 3 to internal Pin index or -1 if pin is reserved */
|
||||||
|
2, 3, 4, 5, /* arduino pin 4 - 7 to internal Pin index or -1 if pin is reserved */
|
||||||
|
6, 7, 8, 9, /* arduino pin 8 - 11 to internal Pin index or -1 if pin is reserved */
|
||||||
|
10, 11, 12, 13, /* arduino pin 12, 13, A0, A1 to internal Pin index or -1 if pin is reserved */
|
||||||
|
14, 15, 16, 17, /* arduino pin A2 - A5 / 16 - 19 to internal Pin index or -1 if pin is reserved */
|
||||||
|
18, 19 }; /* arduino pin A6, A7 to internal Pin index or -1 if pin is reserved */
|
||||||
|
|
||||||
|
/* Map from sketch internal pin index to real chip IO pin number */
|
||||||
|
short internalPins[MAX_PIN] =
|
||||||
|
{ 2, 3, 4, 5, /* index 0 - 3 map to pins 2 - 5 */
|
||||||
|
6, 7, 8, 9, /* index 4 - 7 map to pins 6 - 9 */
|
||||||
|
10, 11, 12, 13, /* index 8 - 11 map to pins 10 - 13 */
|
||||||
|
14, 15, 16, 17, /* index 12 - 15 map to pins A0 - A3 */
|
||||||
|
18, 19, 20, 21 }; /* index 16 - 19 map to pins A4 - A7 */
|
||||||
|
|
||||||
|
uint8_t analogPins[MAX_PIN] =
|
||||||
|
{ 0,0,0,0, /* everything is digital by default */
|
||||||
|
0,0,0,0,
|
||||||
|
0,0,0,0,
|
||||||
|
0,0,0,0,
|
||||||
|
0,0,0,0 };
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
/* first and last pin at port PB, PC and PD for arduino uno/nano */
|
/* first and last pin at port PB, PC and PD for arduino uno/nano */
|
||||||
uint8_t firstPin[] = {8, 14, 0}; // aPin -> allowedPins[] -> pinIndex
|
uint8_t firstPin[] = {8, 14, 0}; // aPin -> allowedPins[] -> pinIndex
|
||||||
@ -210,7 +349,7 @@ uint32_t intervalMax = 60000; // default 60 sec - report after this time i
|
|||||||
uint32_t intervalSml = 2000; // default 2 secs - continue count if timeDiff is less and intervalMax not over
|
uint32_t intervalSml = 2000; // default 2 secs - continue count if timeDiff is less and intervalMax not over
|
||||||
uint16_t countMin = 2; // continue counting if count is less than this and intervalMax not over
|
uint16_t countMin = 2; // continue counting if count is less than this and intervalMax not over
|
||||||
|
|
||||||
uint32_t timeNextReport;
|
uint32_t lastReportCall;
|
||||||
#ifdef ESP8266
|
#ifdef ESP8266
|
||||||
uint32_t expectK;
|
uint32_t expectK;
|
||||||
#endif
|
#endif
|
||||||
@ -428,6 +567,7 @@ uint8_t AddPinChangeInterrupt(uint8_t rPin) {
|
|||||||
|
|
||||||
void ESPISR4() { // ISR for real pin GPIO 4 / pinIndex 2
|
void ESPISR4() { // ISR for real pin GPIO 4 / pinIndex 2
|
||||||
doCount(2, digitalRead(4), millis());
|
doCount(2, digitalRead(4), millis());
|
||||||
|
// called with pinIndex, level, now
|
||||||
}
|
}
|
||||||
|
|
||||||
void ESPISR5() { // ISR for real pin GPIO 5 / pinIndex 1
|
void ESPISR5() { // ISR for real pin GPIO 5 / pinIndex 1
|
||||||
@ -506,6 +646,16 @@ void showIntervals() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
void showThresholds() {
|
||||||
|
Output->print(F("T"));
|
||||||
|
Output->print(analogThresholdMin);
|
||||||
|
Output->print(F(" "));
|
||||||
|
Output->println(analogThresholdMax);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
void showPinConfig(short pinIndex) {
|
void showPinConfig(short pinIndex) {
|
||||||
Output->print(F("P"));
|
Output->print(F("P"));
|
||||||
Output->print(activePin[pinIndex]);
|
Output->print(activePin[pinIndex]);
|
||||||
@ -533,7 +683,10 @@ void showPinHistory(short pinIndex, uint32_t now) {
|
|||||||
if (histPin[hi] == pinIndex)
|
if (histPin[hi] == pinIndex)
|
||||||
if (first || (last <= histTime[hi]+histLen[hi])) count++;
|
if (first || (last <= histTime[hi]+histLen[hi])) count++;
|
||||||
}
|
}
|
||||||
if (!count) return;
|
if (!count) {
|
||||||
|
// Output->println (F("M No Pin History"));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
Output->print (F("H")); // start with H
|
Output->print (F("H")); // start with H
|
||||||
Output->print (activePin[pinIndex]); // printed pin number
|
Output->print (activePin[pinIndex]); // printed pin number
|
||||||
@ -668,12 +821,12 @@ void showPinCounter(short pinIndex, boolean showOnly, uint32_t now) {
|
|||||||
boolean reportDue() {
|
boolean reportDue() {
|
||||||
uint32_t now = millis();
|
uint32_t now = millis();
|
||||||
boolean doReport = false; // check if report needs to be called
|
boolean doReport = false; // check if report needs to be called
|
||||||
if((long)(now - timeNextReport) >= 0) // works fine when millis wraps.
|
if((now - lastReportCall) >= intervalMin) // works fine when millis wraps.
|
||||||
doReport = true; // intervalMin is over
|
doReport = true; // intervalMin is over
|
||||||
else
|
else
|
||||||
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++)
|
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++)
|
||||||
if (activePin[pinIndex] > 0)
|
if (activePin[pinIndex] >= 0)
|
||||||
if((long)(now - (lastReport[pinIndex] + intervalMax)) >= 0)
|
if((now - lastReport[pinIndex]) >= intervalMax)
|
||||||
doReport = true; // active pin has not been reported for langer than intervalMax
|
doReport = true; // active pin has not been reported for langer than intervalMax
|
||||||
return doReport;
|
return doReport;
|
||||||
}
|
}
|
||||||
@ -710,7 +863,7 @@ void report() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
timeNextReport = now + intervalMin; // check again after intervalMin or if intervalMax is over for a pin
|
lastReportCall = now; // check again after intervalMin or if intervalMax is over for a pin
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -720,9 +873,16 @@ void showCmd() {
|
|||||||
Output->print(F("M Status: "));
|
Output->print(F("M Status: "));
|
||||||
printVersionMsg();
|
printVersionMsg();
|
||||||
Output->println();
|
Output->println();
|
||||||
|
|
||||||
showIntervals();
|
showIntervals();
|
||||||
|
#ifdef analogIR
|
||||||
|
showThresholds();
|
||||||
|
#endif
|
||||||
|
Output->print(F("V"));
|
||||||
|
Output->println(devVerbose);
|
||||||
|
|
||||||
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++) {
|
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++) {
|
||||||
if (activePin[pinIndex] > 0) {
|
if (activePin[pinIndex] >= 0) {
|
||||||
showPinConfig(pinIndex);
|
showPinConfig(pinIndex);
|
||||||
Output->print(F(", "));
|
Output->print(F(", "));
|
||||||
showPinCounter(pinIndex, true, now);
|
showPinCounter(pinIndex, true, now);
|
||||||
@ -733,10 +893,9 @@ void showCmd() {
|
|||||||
}
|
}
|
||||||
readFromEEPROM();
|
readFromEEPROM();
|
||||||
Output->print(F("M Next report in "));
|
Output->print(F("M Next report in "));
|
||||||
Output->print(timeNextReport - millis());
|
Output->print(lastReportCall + intervalMin - millis());
|
||||||
Output->print(F(" milliseconds"));
|
Output->print(F(" milliseconds"));
|
||||||
Output->println();
|
Output->println();
|
||||||
//Output->println(F("M #end#"));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -768,6 +927,12 @@ void helloCmd() {
|
|||||||
|
|
||||||
Output->println();
|
Output->println();
|
||||||
showIntervals();
|
showIntervals();
|
||||||
|
#ifdef analogIR
|
||||||
|
showThresholds();
|
||||||
|
#endif
|
||||||
|
Output->print(F("V"));
|
||||||
|
Output->println(devVerbose);
|
||||||
|
|
||||||
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++) { // go through all observed pins as pinIndex
|
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++) { // go through all observed pins as pinIndex
|
||||||
if (activePin[pinIndex] >= 0) {
|
if (activePin[pinIndex] >= 0) {
|
||||||
showPinConfig(pinIndex);
|
showPinConfig(pinIndex);
|
||||||
@ -785,7 +950,7 @@ void addCmd(uint16_t *values, uint8_t size) {
|
|||||||
uint16_t pulseWidth;
|
uint16_t pulseWidth;
|
||||||
uint32_t now = millis();
|
uint32_t now = millis();
|
||||||
|
|
||||||
uint8_t aPin = values[0]; // value 0 is pin number
|
uint8_t aPin = values[0]; // values[0] is pin number
|
||||||
if (aPin >= MAX_APIN || allowedPins[aPin] < 0) {
|
if (aPin >= MAX_APIN || allowedPins[aPin] < 0) {
|
||||||
PrintErrorMsg();
|
PrintErrorMsg();
|
||||||
Output->print(F("Illegal pin specification "));
|
Output->print(F("Illegal pin specification "));
|
||||||
@ -804,18 +969,20 @@ void addCmd(uint16_t *values, uint8_t size) {
|
|||||||
activePin[pinIndex] = aPin; // save arduino pin number and flag this pin as active for reporting
|
activePin[pinIndex] = aPin; // save arduino pin number and flag this pin as active for reporting
|
||||||
}
|
}
|
||||||
|
|
||||||
if (values[1] < 2 || values[1] > 3) { // value 1 is level (rising / falling -> 0/1
|
if (values[1] < 2 || values[1] > 3) { // values[1] is level (3->rising / 2->falling)
|
||||||
PrintErrorMsg();
|
PrintErrorMsg();
|
||||||
Output->print(F("Illegal pulse level specification for pin "));
|
Output->print(F("Illegal pulse level specification for pin "));
|
||||||
Output->println(aPin);
|
Output->println(aPin);
|
||||||
}
|
}
|
||||||
pulseLevel[pinIndex] = (values[1] == 3); // 2 = falling -> pulseLevel 0, 3 = rising -> pulseLevel 1
|
pulseLevel[pinIndex] = (values[1] == 3); // 2 = falling -> pulseLevel 0, 3 = rising -> pulseLevel 1
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
if (size > 2 && values[2]) { // value 2 is pullup
|
if (size > 2 && values[2] && !analogPins[pinIndex]) {
|
||||||
pinMode (rPin, INPUT_PULLUP);
|
#else
|
||||||
|
if (size > 2 && values[2]) {
|
||||||
|
#endif
|
||||||
|
pinMode (rPin, INPUT_PULLUP); // values[2] is pullup flag
|
||||||
pullup[pinIndex] = 1;
|
pullup[pinIndex] = 1;
|
||||||
// digitalWrite (rPin, HIGH); // old way to enable pullup resistor
|
|
||||||
} else {
|
} else {
|
||||||
pinMode (rPin, INPUT);
|
pinMode (rPin, INPUT);
|
||||||
pullup[pinIndex] = 0;
|
pullup[pinIndex] = 0;
|
||||||
@ -826,14 +993,22 @@ void addCmd(uint16_t *values, uint8_t size) {
|
|||||||
} else {
|
} else {
|
||||||
pulseWidth = 2;
|
pulseWidth = 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* todo: add upper and lower limits for analog pins as option here and in Fhem module */
|
||||||
|
|
||||||
pulseWidthMin[pinIndex] = pulseWidth;
|
pulseWidthMin[pinIndex] = pulseWidth;
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
if (!analogPins[pinIndex]) {
|
||||||
|
#endif
|
||||||
if (!AddPinChangeInterrupt(rPin)) { // add Pin Change Interrupt
|
if (!AddPinChangeInterrupt(rPin)) { // add Pin Change Interrupt
|
||||||
PrintErrorMsg();
|
PrintErrorMsg();
|
||||||
Output->println(F("AddInt"));
|
Output->println(F("AddInt"));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#ifdef analogIR
|
||||||
|
}
|
||||||
|
#endif
|
||||||
Output->print(F("M defined "));
|
Output->print(F("M defined "));
|
||||||
showPinConfig(pinIndex);
|
showPinConfig(pinIndex);
|
||||||
Output->println();
|
Output->println();
|
||||||
@ -853,6 +1028,9 @@ void removeCmd(uint16_t *values, uint8_t size) {
|
|||||||
};
|
};
|
||||||
uint8_t pinIndex = allowedPins[aPin];
|
uint8_t pinIndex = allowedPins[aPin];
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
if (!analogPins[pinIndex]) {
|
||||||
|
#endif
|
||||||
#ifdef ESP8266
|
#ifdef ESP8266
|
||||||
detachInterrupt(digitalPinToInterrupt(internalPins[pinIndex]));
|
detachInterrupt(digitalPinToInterrupt(internalPins[pinIndex]));
|
||||||
#else
|
#else
|
||||||
@ -860,6 +1038,9 @@ void removeCmd(uint16_t *values, uint8_t size) {
|
|||||||
PrintErrorMsg(); Output->println(F("RemInt"));
|
PrintErrorMsg(); Output->println(F("RemInt"));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#ifdef analogIR
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
initPinVars(pinIndex, 0);
|
initPinVars(pinIndex, 0);
|
||||||
Output->print(F("M removed "));
|
Output->print(F("M removed "));
|
||||||
@ -882,8 +1063,6 @@ void intervalCmd(uint16_t *values, uint8_t size) {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
intervalMin = (long)values[0] * 1000;
|
intervalMin = (long)values[0] * 1000;
|
||||||
if (millis() + intervalMin < timeNextReport)
|
|
||||||
timeNextReport = millis() + intervalMin;
|
|
||||||
|
|
||||||
if (values[1] < 1 || values[1] > 3600) {
|
if (values[1] < 1 || values[1] > 3600) {
|
||||||
PrintErrorMsg(); Output->println(values[1]);
|
PrintErrorMsg(); Output->println(values[1]);
|
||||||
@ -914,9 +1093,47 @@ void intervalCmd(uint16_t *values, uint8_t size) {
|
|||||||
Output->println();
|
Output->println();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
void thresholdCmd(uint16_t *values, uint8_t size) {
|
||||||
|
/*Serial.print(F("D threshold size "));
|
||||||
|
Serial.print(size);
|
||||||
|
Serial.print(F(" v0 "));
|
||||||
|
Serial.print(values[0]);
|
||||||
|
Serial.print(F(" v1 "));
|
||||||
|
Serial.print(values[1]);
|
||||||
|
Serial.println();*/
|
||||||
|
|
||||||
|
if (size < 2) { // t command gets 2 values: min, max
|
||||||
|
PrintErrorMsg();
|
||||||
|
Output->print(F("size"));
|
||||||
|
Output->println();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (values[0] < 1 || values[0] > 1023) {
|
||||||
|
PrintErrorMsg(); Output->println(values[0]);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
analogThresholdMin = (int)values[0];
|
||||||
|
|
||||||
|
if (values[1] < 1 || values[1] > 1023) {
|
||||||
|
PrintErrorMsg(); Output->println(values[1]);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
analogThresholdMax = (int)values[1];
|
||||||
|
|
||||||
|
Output->print(F("M analog thresholds set to "));
|
||||||
|
Output->print(values[0]);
|
||||||
|
Output->print(F(" "));
|
||||||
|
Output->print(values[1]);
|
||||||
|
Output->println();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
void keepAliveCmd(uint16_t *values, uint8_t size) {
|
void keepAliveCmd(uint16_t *values, uint8_t size) {
|
||||||
|
if (values[0] == 1 && size > 0) {
|
||||||
Output->println(F("alive"));
|
Output->println(F("alive"));
|
||||||
|
}
|
||||||
#ifdef ESP8266
|
#ifdef ESP8266
|
||||||
if (values[0] == 1 && size > 0 && size < 3 && Client1.connected()) {
|
if (values[0] == 1 && size > 0 && size < 3 && Client1.connected()) {
|
||||||
tcpMode = true;
|
tcpMode = true;
|
||||||
@ -965,6 +1182,7 @@ void updateEEPROMSlot(int &address, char cmd, int v1, int v2, int v3, int v4) {
|
|||||||
updateEEPROM(address, v4 >> 8);
|
updateEEPROM(address, v4 >> 8);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* todo: include analogPins as well as analog limits in save / restore */
|
||||||
|
|
||||||
void saveToEEPROMCmd() {
|
void saveToEEPROMCmd() {
|
||||||
int address = 0;
|
int address = 0;
|
||||||
@ -973,12 +1191,18 @@ void saveToEEPROMCmd() {
|
|||||||
updateEEPROM(address, 'f');
|
updateEEPROM(address, 'f');
|
||||||
updateEEPROM(address, 'g');
|
updateEEPROM(address, 'g');
|
||||||
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++)
|
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++)
|
||||||
if (activePin[pinIndex] > 0) slots ++;
|
if (activePin[pinIndex] >= 0) slots ++;
|
||||||
|
#ifdef analogIR
|
||||||
|
slots ++;
|
||||||
|
#endif
|
||||||
updateEEPROM(address, slots); // number of defined pins + intervall definition
|
updateEEPROM(address, slots); // number of defined pins + intervall definition
|
||||||
updateEEPROMSlot(address, 'I', (uint16_t)(intervalMin / 1000), (uint16_t)(intervalMax / 1000),
|
updateEEPROMSlot(address, 'I', (uint16_t)(intervalMin / 1000), (uint16_t)(intervalMax / 1000),
|
||||||
(uint16_t)(intervalSml / 1000), (uint16_t)countMin);
|
(uint16_t)(intervalSml / 1000), (uint16_t)countMin);
|
||||||
|
#ifdef analogIR
|
||||||
|
updateEEPROMSlot(address, 'T', (uint16_t)analogThresholdMin, (uint16_t)analogThresholdMax, 0, 0);
|
||||||
|
#endif
|
||||||
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++)
|
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++)
|
||||||
if (activePin[pinIndex] > 0)
|
if (activePin[pinIndex] >= 0)
|
||||||
updateEEPROMSlot(address, 'A', (uint16_t)activePin[pinIndex], (uint16_t)(pulseLevel[pinIndex] ? 3:2),
|
updateEEPROMSlot(address, 'A', (uint16_t)activePin[pinIndex], (uint16_t)(pulseLevel[pinIndex] ? 3:2),
|
||||||
(uint16_t)pullup[pinIndex], (uint16_t)pulseWidthMin[pinIndex]);
|
(uint16_t)pullup[pinIndex], (uint16_t)pulseWidthMin[pinIndex]);
|
||||||
#ifdef ESP8266
|
#ifdef ESP8266
|
||||||
@ -993,6 +1217,18 @@ void saveToEEPROMCmd() {
|
|||||||
|
|
||||||
void readFromEEPROM() {
|
void readFromEEPROM() {
|
||||||
int address = 0;
|
int address = 0;
|
||||||
|
uint16_t v1, v2, v3, v4;
|
||||||
|
char cmd;
|
||||||
|
if (EEPROM.read(address) != 'C' || EEPROM.read(address+1) != 'f' || EEPROM.read(address+2) != 'g') {
|
||||||
|
Output->println(F("M no config in EEPROM"));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
address = 3;
|
||||||
|
uint8_t slots = EEPROM.read(address++);
|
||||||
|
if (slots > MAX_PIN + 2) {
|
||||||
|
Output->println(F("M illegal config in EEPROM"));
|
||||||
|
return;
|
||||||
|
}
|
||||||
Output->println();
|
Output->println();
|
||||||
Output->print(F("M EEPROM Config: "));
|
Output->print(F("M EEPROM Config: "));
|
||||||
Output->print((char) EEPROM.read(0));
|
Output->print((char) EEPROM.read(0));
|
||||||
@ -1001,18 +1237,6 @@ void readFromEEPROM() {
|
|||||||
Output->print(F(" Slots: "));
|
Output->print(F(" Slots: "));
|
||||||
Output->print((int) EEPROM.read(3));
|
Output->print((int) EEPROM.read(3));
|
||||||
Output->println();
|
Output->println();
|
||||||
if (EEPROM.read(address) != 'C' || EEPROM.read(address+1) != 'f' || EEPROM.read(address+2) != 'g') {
|
|
||||||
Output->println(F("M no config in EEPROM"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
address = 3;
|
|
||||||
uint8_t slots = EEPROM.read(address++);
|
|
||||||
if (slots > MAX_PIN + 1) {
|
|
||||||
Output->println(F("M illegal config in EEPROM"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
uint16_t v1, v2, v3, v4;
|
|
||||||
char cmd;
|
|
||||||
for (uint8_t slot=0; slot < slots; slot++) {
|
for (uint8_t slot=0; slot < slots; slot++) {
|
||||||
cmd = EEPROM.read(address);
|
cmd = EEPROM.read(address);
|
||||||
v1 = EEPROM.read(address+1) + (((uint16_t)EEPROM.read(address+2)) << 8);
|
v1 = EEPROM.read(address+1) + (((uint16_t)EEPROM.read(address+2)) << 8);
|
||||||
@ -1058,6 +1282,9 @@ void restoreFromEEPROM() {
|
|||||||
address = address + 9;
|
address = address + 9;
|
||||||
commandDataPointer = 4;
|
commandDataPointer = 4;
|
||||||
if (cmd == 'I') intervalCmd(commandData, commandDataPointer);
|
if (cmd == 'I') intervalCmd(commandData, commandDataPointer);
|
||||||
|
#ifdef analogIR
|
||||||
|
if (cmd == 'T') thresholdCmd(commandData, commandDataPointer);
|
||||||
|
#endif
|
||||||
if (cmd == 'A') addCmd(commandData, commandDataPointer);
|
if (cmd == 'A') addCmd(commandData, commandDataPointer);
|
||||||
}
|
}
|
||||||
commandDataPointer = 0;
|
commandDataPointer = 0;
|
||||||
@ -1081,6 +1308,7 @@ void handleInput(char c) {
|
|||||||
else if ('a' <= c && c <= 'z') { // letter input is command
|
else if ('a' <= c && c <= 'z') { // letter input is command
|
||||||
|
|
||||||
if (devVerbose > 0) {
|
if (devVerbose > 0) {
|
||||||
|
commandData[commandDataPointer] = value;
|
||||||
Serial.print(F("D got "));
|
Serial.print(F("D got "));
|
||||||
for (short v = 0; v <= commandDataPointer; v++) {
|
for (short v = 0; v <= commandDataPointer; v++) {
|
||||||
if (v > 0) Serial.print(F(","));
|
if (v > 0) Serial.print(F(","));
|
||||||
@ -1093,25 +1321,49 @@ void handleInput(char c) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
switch (c) {
|
switch (c) {
|
||||||
case 'a':
|
case 'a': // add a pin
|
||||||
commandData[commandDataPointer] = value;
|
commandData[commandDataPointer] = value;
|
||||||
addCmd(commandData, commandDataPointer+1);
|
addCmd(commandData, commandDataPointer+1);
|
||||||
break;
|
break;
|
||||||
case 'd':
|
case 'd': // delete a pin
|
||||||
commandData[commandDataPointer] = value;
|
commandData[commandDataPointer] = value;
|
||||||
removeCmd(commandData, commandDataPointer+1);
|
removeCmd(commandData, commandDataPointer+1);
|
||||||
break;
|
break;
|
||||||
case 'i':
|
case 'e': // save to EEPROM
|
||||||
|
saveToEEPROMCmd();
|
||||||
|
break;
|
||||||
|
case 'f': // flash ota
|
||||||
|
// OTA flash from HTTP Server
|
||||||
|
break;
|
||||||
|
case 'h': // hello
|
||||||
|
helloCmd();
|
||||||
|
break;
|
||||||
|
case 'i': // interval
|
||||||
commandData[commandDataPointer] = value;
|
commandData[commandDataPointer] = value;
|
||||||
intervalCmd(commandData, commandDataPointer+1);
|
intervalCmd(commandData, commandDataPointer+1);
|
||||||
break;
|
break;
|
||||||
case 'r':
|
case 'k': // keep alive
|
||||||
|
commandData[commandDataPointer] = value;
|
||||||
|
keepAliveCmd(commandData, commandDataPointer+1);
|
||||||
|
break;
|
||||||
|
#ifdef ESP8266
|
||||||
|
case 'q': // quit
|
||||||
|
quitCmd();
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
case 'r': // reset
|
||||||
initialize();
|
initialize();
|
||||||
break;
|
break;
|
||||||
case 's':
|
case 's': // show
|
||||||
showCmd();
|
showCmd();
|
||||||
break;
|
break;
|
||||||
case 'v':
|
#ifdef analogIR
|
||||||
|
case 't': // thresholds for analog pin
|
||||||
|
commandData[commandDataPointer] = value;
|
||||||
|
thresholdCmd(commandData, commandDataPointer+1);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
case 'v': // dev verbose
|
||||||
if (value < 255) {
|
if (value < 255) {
|
||||||
devVerbose = value;
|
devVerbose = value;
|
||||||
Output->print(F("M devVerbose set to "));
|
Output->print(F("M devVerbose set to "));
|
||||||
@ -1120,24 +1372,6 @@ void handleInput(char c) {
|
|||||||
Output->println(F("M illegal value passed for devVerbose"));
|
Output->println(F("M illegal value passed for devVerbose"));
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'h':
|
|
||||||
helloCmd();
|
|
||||||
break;
|
|
||||||
case 'e':
|
|
||||||
saveToEEPROMCmd();
|
|
||||||
break;
|
|
||||||
case 'f':
|
|
||||||
// OTA flash from HTTP Server
|
|
||||||
break;
|
|
||||||
#ifdef ESP8266
|
|
||||||
case 'q':
|
|
||||||
quitCmd();
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
case 'k':
|
|
||||||
commandData[commandDataPointer] = value;
|
|
||||||
keepAliveCmd(commandData, commandDataPointer+1);
|
|
||||||
break;
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -1192,18 +1426,18 @@ void debugPinChanges() {
|
|||||||
lastState[pinIndex] = pinState;
|
lastState[pinIndex] = pinState;
|
||||||
Output->print(F("M pin "));
|
Output->print(F("M pin "));
|
||||||
Output->print(aPin);
|
Output->print(aPin);
|
||||||
Output->print(F(" ( internal "));
|
Output->print(F(" (internal "));
|
||||||
Output->print(rPin);
|
Output->print(rPin);
|
||||||
Output->print(F(" ) "));
|
Output->print(F(")"));
|
||||||
Output->print(F(" to "));
|
Output->print(F(" changed to "));
|
||||||
Output->print(pinState);
|
Output->print(pinState);
|
||||||
#ifdef pulseHistory
|
#ifdef pulseHistory
|
||||||
Output->print(F(" histIdx "));
|
Output->print(F(", histIdx "));
|
||||||
Output->print(histIndex);
|
Output->print(histIndex);
|
||||||
#endif
|
#endif
|
||||||
Output->print(F(" count "));
|
Output->print(F(", count "));
|
||||||
Output->print(counter[pinIndex]);
|
Output->print(counter[pinIndex]);
|
||||||
Output->print(F(" reject "));
|
Output->print(F(", reject "));
|
||||||
Output->print(rejectCounter[pinIndex]);
|
Output->print(rejectCounter[pinIndex]);
|
||||||
Output->println();
|
Output->println();
|
||||||
}
|
}
|
||||||
@ -1316,7 +1550,60 @@ void handleTime() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
void detectTrigger(int val) {
|
||||||
|
uint8_t nextState = triggerState;
|
||||||
|
if (val > analogThresholdMax) {
|
||||||
|
nextState = 1;
|
||||||
|
} else if (val < analogThresholdMin) {
|
||||||
|
nextState = 0;
|
||||||
|
}
|
||||||
|
if (nextState != triggerState) {
|
||||||
|
triggerState = nextState;
|
||||||
|
#ifdef ledOutPin
|
||||||
|
digitalWrite(ledOutPin, triggerState);
|
||||||
|
#endif
|
||||||
|
short pinIndex = allowedPins[analogInPin]; // ESP pin A0 (pinIndex 8, internal 17) or Arduino A7 (pinIndex 17, internal 21)
|
||||||
|
uint32_t now = millis();
|
||||||
|
doCount (pinIndex, triggerState, now); // do the counting, history and so on
|
||||||
|
|
||||||
|
if (devVerbose >= 10) {
|
||||||
|
Output->print(F("M called doCount with pinIndex "));
|
||||||
|
Output->print(pinIndex);
|
||||||
|
Output->print(F(" and triggerState"));
|
||||||
|
Output->print(triggerState);
|
||||||
|
Output->println();
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef debugPins
|
||||||
|
if (devVerbose >= 10) {
|
||||||
|
short rPin = internalPins[pinIndex];
|
||||||
|
Output->print(F("M pin "));
|
||||||
|
Output->print(analogInPin);
|
||||||
|
Output->print(F(" (index "));
|
||||||
|
Output->print(pinIndex);
|
||||||
|
Output->print(F(", internal "));
|
||||||
|
Output->print(rPin);
|
||||||
|
Output->print(F(" ) "));
|
||||||
|
Output->print(F(" to "));
|
||||||
|
Output->print(nextState);
|
||||||
|
#ifdef pulseHistory
|
||||||
|
Output->print(F(" histIdx "));
|
||||||
|
Output->print(histIndex);
|
||||||
|
#endif
|
||||||
|
Output->print(F(" count "));
|
||||||
|
Output->print(counter[pinIndex]);
|
||||||
|
Output->print(F(" reject "));
|
||||||
|
Output->print(rejectCounter[pinIndex]);
|
||||||
|
Output->println();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void initPinVars(short pinIndex, uint32_t now) {
|
void initPinVars(short pinIndex, uint32_t now) {
|
||||||
|
uint8_t level = 0;
|
||||||
activePin[pinIndex] = -1; // inactive (-1)
|
activePin[pinIndex] = -1; // inactive (-1)
|
||||||
initialized[pinIndex] = false; // no pulse seen yet
|
initialized[pinIndex] = false; // no pulse seen yet
|
||||||
pulseWidthMin[pinIndex] = 0; // min pulse length
|
pulseWidthMin[pinIndex] = 0; // min pulse length
|
||||||
@ -1330,11 +1617,18 @@ void initPinVars(short pinIndex, uint32_t now) {
|
|||||||
lastChange[pinIndex] = now;
|
lastChange[pinIndex] = now;
|
||||||
lastReport[pinIndex] = now;
|
lastReport[pinIndex] = now;
|
||||||
reportSequence[pinIndex] = 0;
|
reportSequence[pinIndex] = 0;
|
||||||
uint8_t level = digitalRead(internalPins[pinIndex]);
|
#ifdef analogIR
|
||||||
|
if (!analogPins[pinIndex]) {
|
||||||
|
level = digitalRead(internalPins[pinIndex]);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
level = digitalRead(internalPins[pinIndex]);
|
||||||
|
#endif
|
||||||
lastLevel[pinIndex] = level;
|
lastLevel[pinIndex] = level;
|
||||||
#ifdef debugPins
|
#ifdef debugPins
|
||||||
lastState[pinIndex] = level; // for debug output
|
lastState[pinIndex] = level; // for debug output
|
||||||
#endif
|
#endif
|
||||||
|
/* todo: add analogPins, upper and lower limits for analog */
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -1343,7 +1637,7 @@ void initialize() {
|
|||||||
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++) {
|
for (uint8_t pinIndex=0; pinIndex < MAX_PIN; pinIndex++) {
|
||||||
initPinVars(pinIndex, now);
|
initPinVars(pinIndex, now);
|
||||||
}
|
}
|
||||||
timeNextReport = now + intervalMin; // time for first output
|
lastReportCall = now; // time for first output after intervalMin from now
|
||||||
devVerbose = 0;
|
devVerbose = 0;
|
||||||
#ifndef ESP8266
|
#ifndef ESP8266
|
||||||
for (uint8_t port=0; port <= 2; port++) {
|
for (uint8_t port=0; port <= 2; port++) {
|
||||||
@ -1374,6 +1668,12 @@ void setup() {
|
|||||||
millisWraps = 0;
|
millisWraps = 0;
|
||||||
lastMillis = millis();
|
lastMillis = millis();
|
||||||
initialize();
|
initialize();
|
||||||
|
#ifdef analogIR
|
||||||
|
pinMode(irOutPin, OUTPUT);
|
||||||
|
#ifdef ledOutPin
|
||||||
|
pinMode(ledOutPin, OUTPUT);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
helloCmd(); // started message to serial
|
helloCmd(); // started message to serial
|
||||||
#ifdef ESP8266
|
#ifdef ESP8266
|
||||||
connectWiFi();
|
connectWiFi();
|
||||||
@ -1381,21 +1681,41 @@ void setup() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/* Main Loop */
|
||||||
Main Loop
|
|
||||||
checks if report should be called because timeNextReport is reached
|
|
||||||
or lastReport for one pin is older than intervalMax
|
|
||||||
timeNextReport is only set here (and when interval is changed / at setup)
|
|
||||||
*/
|
|
||||||
void loop() {
|
void loop() {
|
||||||
handleTime();
|
handleTime();
|
||||||
if (Serial.available()) {
|
if (Serial.available()) handleInput(Serial.read());
|
||||||
handleInput(Serial.read());
|
|
||||||
}
|
|
||||||
#ifdef ESP8266
|
#ifdef ESP8266
|
||||||
handleConnections();
|
handleConnections();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef analogIR
|
||||||
|
short AIndex = allowedPins[analogInPin];
|
||||||
|
if (AIndex >= 0 && activePin[AIndex] >= 0) {
|
||||||
|
digitalWrite(irOutPin, LOW);
|
||||||
|
// wait 10 milliseconds
|
||||||
|
delay(10);
|
||||||
|
// read the analog in value:
|
||||||
|
sensorValueOff = analogRead(analogInPin);
|
||||||
|
// turn IR LED on
|
||||||
|
digitalWrite(irOutPin, HIGH);
|
||||||
|
delay(10);
|
||||||
|
// read the analog in value:
|
||||||
|
sensorValueOn = analogRead(analogInPin);
|
||||||
|
detectTrigger (sensorValueOn - sensorValueOff);
|
||||||
|
if (devVerbose >= 20) {
|
||||||
|
Output->print(F("L"));
|
||||||
|
|
||||||
|
Output->print(sensorValueOn);
|
||||||
|
Output->print(F(","));
|
||||||
|
Output->print(sensorValueOff);
|
||||||
|
Output->print(F("->"));
|
||||||
|
|
||||||
|
Output->println(sensorValueOn - sensorValueOff);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef debugPins
|
#ifdef debugPins
|
||||||
if (devVerbose >= 10) {
|
if (devVerbose >= 10) {
|
||||||
debugPinChanges();
|
debugPinChanges();
|
||||||
@ -1406,4 +1726,3 @@ void loop() {
|
|||||||
report();
|
report();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
x
Reference in New Issue
Block a user