Compare commits
52 Commits
nano-revis
...
main
13 changed files with 654 additions and 152 deletions
Binary file not shown.
Binary file not shown.
@ -1,3 +1,5 @@ |
|||||||
| Board | Button Interrupt | RS485-Interrupt | RS485/A | RS485/B | |
| Board | Button Interrupt | RS485-Interrupt | RS485/A | RS485/B | |
||||||
|-------|------------------|-----------------|---------|---------| |
|-------|------------------|-----------------|---------|---------| |
||||||
| 1.0 | D2 | D3 | U7 | U8 | |
| 1.0 | D2 | D3 | U7 | U8 | |
||||||
|
| 2.0 | D2 | (D10)| U8 | U7 | |
||||||
|
| 2.1 | D3 | D2 | U8 | U7 | |
@ -1,59 +0,0 @@ |
|||||||
int sTx = 2; |
|
||||||
int sRx = 3; |
|
||||||
|
|
||||||
long base = 100; |
|
||||||
long rst = base*10; // reset
|
|
||||||
boolean bt = false; |
|
||||||
long dif = 0; |
|
||||||
long lt = 0; |
|
||||||
long now = 0; |
|
||||||
char rcv = 0; |
|
||||||
int idx = 0; |
|
||||||
String message; |
|
||||||
void setup(){ |
|
||||||
pinMode(sRx,INPUT); |
|
||||||
pinMode(sTx,OUTPUT); |
|
||||||
attachInterrupt(digitalPinToInterrupt(sRx),change,CHANGE); |
|
||||||
Serial.begin(115200);
|
|
||||||
Serial.println("Receiver ready"); |
|
||||||
} |
|
||||||
|
|
||||||
void reset(long dif){ |
|
||||||
rcv = 0; |
|
||||||
idx = -1; |
|
||||||
message.reserve(32); |
|
||||||
} |
|
||||||
void change(){ |
|
||||||
bool bt = digitalRead(sRx); |
|
||||||
now = micros(); |
|
||||||
dif = now - lt; |
|
||||||
lt = now; |
|
||||||
if (dif > rst){ |
|
||||||
reset(dif); |
|
||||||
} else { |
|
||||||
handle(!bt,dif); |
|
||||||
} |
|
||||||
} |
|
||||||
|
|
||||||
void handle(boolean bt, long dif){ |
|
||||||
long count = dif/base; |
|
||||||
for (int i=0; i<count; i++) push(bt); |
|
||||||
} |
|
||||||
|
|
||||||
void push(boolean bt){ |
|
||||||
if (idx>=0) rcv |= bt<<idx; |
|
||||||
idx++; |
|
||||||
|
|
||||||
if (idx == 8){ |
|
||||||
if (rcv == 13) { |
|
||||||
Serial.println(message); |
|
||||||
message = ""; |
|
||||||
} else { |
|
||||||
message+=rcv; |
|
||||||
}
|
|
||||||
idx =0; |
|
||||||
rcv =0; |
|
||||||
} |
|
||||||
} |
|
||||||
|
|
||||||
void loop(){} |
|
@ -1,93 +0,0 @@ |
|||||||
// Breadboard
|
|
||||||
//int enable = 2;
|
|
||||||
//int sTx = 4;
|
|
||||||
//int sRx = 5;
|
|
||||||
|
|
||||||
// RS485-Nano Revision 1.0
|
|
||||||
int enable = 9; |
|
||||||
int sTx = 8; |
|
||||||
int sRx = 3; |
|
||||||
|
|
||||||
long base = 100; |
|
||||||
|
|
||||||
int id = 0; |
|
||||||
int baud = 19200; |
|
||||||
char c; |
|
||||||
int counter = 0; |
|
||||||
|
|
||||||
void setup(){ |
|
||||||
pinMode(A0,INPUT); |
|
||||||
id = analogRead(A0); |
|
||||||
|
|
||||||
pinMode(enable,OUTPUT); |
|
||||||
digitalWrite(enable,LOW); |
|
||||||
|
|
||||||
pinMode(sTx,OUTPUT); |
|
||||||
digitalWrite(sTx,LOW); |
|
||||||
|
|
||||||
pinMode(sRx,INPUT); |
|
||||||
Serial.begin(115200);
|
|
||||||
Serial.print("Baud rate set to "); |
|
||||||
Serial.println(baud); |
|
||||||
Serial.print("Initialized Arduino #"); |
|
||||||
Serial.println(id); |
|
||||||
} |
|
||||||
|
|
||||||
bool sendBit(bool bt){ |
|
||||||
digitalWrite(sTx,bt); |
|
||||||
delayMicroseconds(80); |
|
||||||
if (digitalRead(sTx) != bt) return false; |
|
||||||
delayMicroseconds(base-80); |
|
||||||
return true; |
|
||||||
} |
|
||||||
|
|
||||||
bool sendChar(char c){ |
|
||||||
return sendBit(c & 0x01) |
|
||||||
&& sendBit(c & 0x02) |
|
||||||
&& sendBit(c & 0x04) |
|
||||||
&& sendBit(c & 0x08) |
|
||||||
&& sendBit(c & 0x10) |
|
||||||
&& sendBit(c & 0x20) |
|
||||||
&& sendBit(c & 0x40) |
|
||||||
&& sendBit(c & 0x80); |
|
||||||
} |
|
||||||
|
|
||||||
bool sendString(String s){ |
|
||||||
Serial.print("Sending '"+s+"'…"); |
|
||||||
boolean busy = false; |
|
||||||
for (int i = 0; i<11; i++){ |
|
||||||
if (!digitalRead(sRx)) { |
|
||||||
if (!busy){ |
|
||||||
Serial.print("busy…"); |
|
||||||
busy = true; |
|
||||||
} |
|
||||||
i = 0; // wait for free line
|
|
||||||
} |
|
||||||
delayMicroseconds(base); |
|
||||||
} |
|
||||||
digitalWrite(enable,HIGH); |
|
||||||
bool success = sendBit(0); // erste Flanke erzeugen
|
|
||||||
if (success) { |
|
||||||
for (char c : s){ |
|
||||||
if (!sendChar(c)){ |
|
||||||
success = false; |
|
||||||
break; |
|
||||||
} |
|
||||||
} |
|
||||||
} |
|
||||||
success = success && sendChar(13); |
|
||||||
success = success && sendBit(1); // letzte Flanke erzeugen
|
|
||||||
digitalWrite(enable,LOW); |
|
||||||
Serial.println(success ? "success" : "failed"); |
|
||||||
return success; |
|
||||||
} |
|
||||||
|
|
||||||
void loop(){ |
|
||||||
counter++; |
|
||||||
String s = "Hier ist "; |
|
||||||
s.concat(id); |
|
||||||
s+=": counter = "; |
|
||||||
s.concat(counter); |
|
||||||
while (!sendString(s)) delay(10*base); |
|
||||||
delay(id); |
|
||||||
} |
|
@ -0,0 +1,63 @@ |
|||||||
|
/*
|
||||||
|
* Demonstrates how to use LCDisplay in conjunction with SoftRS485: |
||||||
|
* |
||||||
|
* The main _loop_ of this program listens on the RS485 bus. |
||||||
|
* Whenever a message is received from the bus, it is displayed on the LCD. |
||||||
|
*/ |
||||||
|
|
||||||
|
// include the library code:
|
||||||
|
#include <LiquidCrystal.h> |
||||||
|
#include <SoftRS485.h> |
||||||
|
|
||||||
|
#define Max485_RO 2 // read-output of Max485
|
||||||
|
#define Max485_RE 8 // not-read-enable of Max485
|
||||||
|
#define Max485_DE 8 // data enable of Max485
|
||||||
|
#define Max485_DI 9 // data input of Max485
|
||||||
|
|
||||||
|
#define LCD_RS 10 |
||||||
|
#define LCD_EN 11 |
||||||
|
#define LCD_D4 4 |
||||||
|
#define LCD_D5 5 |
||||||
|
#define LCD_D6 6 |
||||||
|
#define LCD_D7 7 |
||||||
|
|
||||||
|
#define PROGRAM "RS485-Nano 2.1 / LCDReceive 1.2" |
||||||
|
|
||||||
|
// initialize the library by associating any needed LCD interface pin with the arduino pin number it is connected to
|
||||||
|
LiquidCrystal lcd(LCD_RS, LCD_EN, LCD_D4, LCD_D5, LCD_D6, LCD_D7); |
||||||
|
|
||||||
|
void setup() { |
||||||
|
Serial.begin(115200); |
||||||
|
init485(Max485_RO,Max485_RE,Max485_DE,Max485_DI); // library initialization:
|
||||||
|
|
||||||
|
// set up the LCD's number of columns and rows:
|
||||||
|
lcd.begin(16, 4); |
||||||
|
// Print a message to the LCD.
|
||||||
|
printMessage(PROGRAM); |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
void printMessage(String s){ |
||||||
|
Serial.println(s); |
||||||
|
lcd.clear();
|
||||||
|
int line = 0; |
||||||
|
int col = 0; |
||||||
|
auto cstr = s.c_str(); |
||||||
|
for (int i=0;i<s.length();i++){ |
||||||
|
if (col == 0 && cstr[i] == ' ') continue; |
||||||
|
if (cstr[i] == '{' || cstr[i] == '}') continue; |
||||||
|
lcd.print(cstr[i]); |
||||||
|
col++; |
||||||
|
if (cstr[i]==',' || col==16){ |
||||||
|
line++; |
||||||
|
col=0; |
||||||
|
lcd.setCursor(col, line); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void loop() { |
||||||
|
if (available485()) { |
||||||
|
printMessage(get485message()); |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,85 @@ |
|||||||
|
/*// This sketch allows manual setting of the RS485-connected pins via serial terminal commands
|
||||||
|
|
||||||
|
Commands are: |
||||||
|
r+ – enable read mode (^RE ← LOW) |
||||||
|
r- – disable read mode (^RE ← HIGH) |
||||||
|
w+ – enable write mode (DE ← HIGH) |
||||||
|
w- – disable write mode (DE ← LOW) |
||||||
|
h – send HIGH level on DI |
||||||
|
l – send LOW level on DI |
||||||
|
|
||||||
|
//*/
|
||||||
|
|
||||||
|
#if defined(ARDUINO_AVR_UNO) |
||||||
|
#define RS485_RO 5 |
||||||
|
#define RS485_RE 4 |
||||||
|
#define RS485_DE 3 |
||||||
|
#define RS485_DI 2 |
||||||
|
#define BOARD "Arduino Uno" |
||||||
|
#endif |
||||||
|
#if defined(ARDUINO_AVR_NANO) |
||||||
|
#define RS485_RO 3 |
||||||
|
#define RS485_RE 2 |
||||||
|
#define RS485_DE 4 |
||||||
|
#define RS485_DI 5 |
||||||
|
#define BOARD "Arduino Nano" |
||||||
|
#endif |
||||||
|
|
||||||
|
String command = ""; |
||||||
|
bool doPrint = false; |
||||||
|
// the setup function runs once when you press reset or power the board
|
||||||
|
void setup() { |
||||||
|
// initialize digital pin LED_BUILTIN as an output.
|
||||||
|
pinMode(RS485_RO, INPUT); |
||||||
|
pinMode(RS485_RE, OUTPUT); |
||||||
|
pinMode(RS485_DE, OUTPUT); |
||||||
|
pinMode(RS485_DI, OUTPUT); |
||||||
|
digitalWrite(RS485_RE,LOW); |
||||||
|
digitalWrite(RS485_DE,LOW); |
||||||
|
digitalWrite(RS485_DI,LOW); |
||||||
|
Serial.begin(115200); |
||||||
|
Serial.println(F("this is Projekte/Arduino/MAX485/ManualSend")); |
||||||
|
Serial.println(F("send any of the followning commands:")); |
||||||
|
Serial.println(F("- r+ (enable read)\n- r- (disable read)\n- w+ (enable write)\n- w- (disable write)\n- h (for high)\n- l (for low)")); |
||||||
|
} |
||||||
|
|
||||||
|
// the loop function runs over and over again forever
|
||||||
|
void loop() { |
||||||
|
while (Serial.available()){ |
||||||
|
char inChar = (char)Serial.read(); |
||||||
|
if (inChar == '\n') { |
||||||
|
process(command); |
||||||
|
command = "";
|
||||||
|
doPrint = true; |
||||||
|
} else { |
||||||
|
command += inChar; |
||||||
|
} |
||||||
|
} |
||||||
|
if (doPrint){ |
||||||
|
printState(); |
||||||
|
delay(1000); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void printState(){ |
||||||
|
Serial.print("RE = "); |
||||||
|
Serial.print(1-digitalRead(RS485_RE)); |
||||||
|
Serial.print(", DE = "); |
||||||
|
Serial.print(digitalRead(RS485_DE)); |
||||||
|
Serial.print(", DI = "); |
||||||
|
Serial.print(digitalRead(RS485_DI)); |
||||||
|
Serial.print(", RO = "); |
||||||
|
Serial.println(digitalRead(RS485_RO)); |
||||||
|
} |
||||||
|
|
||||||
|
void process(String command){ |
||||||
|
Serial.print(F("received:")); |
||||||
|
Serial.println(command); |
||||||
|
if (command == "r+") digitalWrite(RS485_RE,LOW); |
||||||
|
if (command == "r-") digitalWrite(RS485_RE,HIGH); |
||||||
|
if (command == "w+") digitalWrite(RS485_DE,HIGH); |
||||||
|
if (command == "w-") digitalWrite(RS485_DE,LOW); |
||||||
|
if (command == "h") digitalWrite(RS485_DI,HIGH); |
||||||
|
if (command == "l") digitalWrite(RS485_DI,LOW); |
||||||
|
printState(); |
||||||
|
} |
@ -0,0 +1,4 @@ |
|||||||
|
Erkenntnisse: |
||||||
|
|
||||||
|
1. Wenn alle Treiber inaktiv sind, also bei allen Teilnehmer DI = Low ist, kommt vom RO ein High-Signal |
||||||
|
2. das High-Signal ist dominant, d.h. wenn mehrere Teilnehmer senden, und mindestens ein Teilnehmer eine 1 auf den Bus legt, erhalten alle am RO einen HIGH-Pegel |
@ -0,0 +1,124 @@ |
|||||||
|
/*
|
||||||
|
* Demonstrates how to use Read Buttons in conjunction with SoftRS485: |
||||||
|
* |
||||||
|
* If a button is pressed, a corresponding flag is set. |
||||||
|
* The main loop checks for the state of those flags and |
||||||
|
* sends a message on the RS485 bus whenever a flag is set. |
||||||
|
*/ |
||||||
|
|
||||||
|
// include the library code:
|
||||||
|
#include <SoftRS485.h> |
||||||
|
|
||||||
|
// 0=Test
|
||||||
|
// 1=Flur
|
||||||
|
// 2=Wohnzimmer
|
||||||
|
// 3=Bad EG
|
||||||
|
// 4=Treppenhaus
|
||||||
|
// 5=Arbeitszimmer
|
||||||
|
// 6=Bad OG
|
||||||
|
|
||||||
|
#define ID 0 |
||||||
|
#define PROGRAM "Sender" |
||||||
|
#define SW_VERSION "1.3" |
||||||
|
#define HW_VERSION "2.1" |
||||||
|
|
||||||
|
#define BTN_INT 3 // button interrupt pin
|
||||||
|
#define Max485_RO 2 // read-output of Max485
|
||||||
|
#define Max485_RE 3 // not-read-enable of Max485
|
||||||
|
#define Max485_DE 8 // data enable of Max485
|
||||||
|
#define Max485_DI 9 // data input of Max485
|
||||||
|
|
||||||
|
#define TRESHOLD 1024 |
||||||
|
#define TRIGGER_LEVEL 200 |
||||||
|
|
||||||
|
//#define DEBUG
|
||||||
|
//#define LOG_TO_SERIAL
|
||||||
|
#define SEND_485 |
||||||
|
|
||||||
|
boolean raw_states[8]; |
||||||
|
boolean states[8]; |
||||||
|
unsigned long capacitor[8]; |
||||||
|
unsigned long times[8]; |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void setup(){ |
||||||
|
for (int i=0; i<8;i++) { |
||||||
|
capacitor[i] = 0; |
||||||
|
raw_states[i] = LOW; |
||||||
|
states[i] = LOW; |
||||||
|
} |
||||||
|
Serial.begin(115200); |
||||||
|
init485(Max485_RO,Max485_RE,Max485_DE,Max485_DI); // library initialization:
|
||||||
|
pinMode(BTN_INT,INPUT_PULLUP); |
||||||
|
pinMode(14,INPUT_PULLUP); |
||||||
|
pinMode(15,INPUT_PULLUP); |
||||||
|
pinMode(16,INPUT_PULLUP); |
||||||
|
pinMode(17,INPUT_PULLUP); |
||||||
|
pinMode(18,INPUT_PULLUP); |
||||||
|
pinMode(19,INPUT_PULLUP); |
||||||
|
pinMode(20,INPUT_PULLUP); |
||||||
|
pinMode(21,INPUT_PULLUP); |
||||||
|
|
||||||
|
attachInterrupt(digitalPinToInterrupt(BTN_INT),isr,CHANGE); |
||||||
|
String s = "{nano:"+String(ID)+",hw:"+HW_VERSION+","+PROGRAM+":"+SW_VERSION+"}"; |
||||||
|
Serial.println(s); |
||||||
|
send485(s.c_str()); |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
Serial.println("14 15 16 17 18 19 20 21"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void isr(){ |
||||||
|
raw_states[0] = analogRead(14)<TRIGGER_LEVEL; |
||||||
|
raw_states[1] = analogRead(15)<TRIGGER_LEVEL; |
||||||
|
raw_states[2] = analogRead(16)<TRIGGER_LEVEL; |
||||||
|
raw_states[3] = analogRead(17)<TRIGGER_LEVEL; |
||||||
|
|
||||||
|
raw_states[4] = analogRead(18)<TRIGGER_LEVEL; |
||||||
|
raw_states[5] = analogRead(19)<TRIGGER_LEVEL; |
||||||
|
raw_states[6] = analogRead(20)<TRIGGER_LEVEL; |
||||||
|
raw_states[7] = analogRead(21)<TRIGGER_LEVEL; |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
for (int i=0;i<8;i++){ |
||||||
|
Serial.print(" "); |
||||||
|
Serial.print(raw_states[i]); |
||||||
|
Serial.print(" "); |
||||||
|
} |
||||||
|
Serial.println(); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void send(int btn, long duration){ |
||||||
|
String s = "{nano:"+String(ID)+",btn:"+String(btn)+",ms:"+String(duration)+"}"; |
||||||
|
#ifdef SEND_485 |
||||||
|
for (int i = 0; i<10; i++){ |
||||||
|
if (send485(s.c_str())) break; |
||||||
|
Serial.println("collision detected, trying again:"); |
||||||
|
} |
||||||
|
#else |
||||||
|
Serial.println(s); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void loop(){ |
||||||
|
unsigned long now = micros(); |
||||||
|
for (int i=0;i<8;i++){ |
||||||
|
// we emulate a capacitor:
|
||||||
|
// when the button is pressed, it slowly loads, if the button is released, it unloads.
|
||||||
|
capacitor[i] = raw_states[i] ? capacitor[i]+1 : capacitor[i]>>1; |
||||||
|
|
||||||
|
// if the capacitor reaches a certain treshold, the state is changed
|
||||||
|
boolean new_state = capacitor[i]>TRESHOLD; |
||||||
|
|
||||||
|
// TODO: drop state after a maximum HIGH time
|
||||||
|
|
||||||
|
// when the state changes, the duration of the last state is calculated
|
||||||
|
if (states[i] != new_state){
|
||||||
|
long diff = (now - times[i])/1000; |
||||||
|
times[i] = now; |
||||||
|
if (states[i]) send(i+1,diff); // old state was HIGH → we are going LOW
|
||||||
|
states[i] = new_state; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,38 @@ |
|||||||
|
/*
|
||||||
|
* Demonstrates how to use LCDisplay in conjunction with SoftRS485: |
||||||
|
* |
||||||
|
* The main _loop_ of this program listens on the RS485 bus. |
||||||
|
* Whenever a message is received from the bus, it is displayed on the LCD. |
||||||
|
*/ |
||||||
|
|
||||||
|
// include the library code:
|
||||||
|
#include <SoftRS485.h> |
||||||
|
|
||||||
|
|
||||||
|
#define Max485_RO 2 // read-output of Max485
|
||||||
|
#define Max485_RE 3 // not-read-enable of Max485
|
||||||
|
#define Max485_DE 8 // data enable of Max485
|
||||||
|
#define Max485_DI 9 // data input of Max485
|
||||||
|
|
||||||
|
#define PROGRAM "{hw:RS485-Nano rev 2.1,firmware:Transceiver,version:1.0}" |
||||||
|
|
||||||
|
String message = ""; |
||||||
|
char c; |
||||||
|
void setup() { |
||||||
|
Serial.begin(115200); |
||||||
|
init485(Max485_RO,Max485_RE,Max485_DE,Max485_DI); // library initialization:
|
||||||
|
send485(PROGRAM); |
||||||
|
} |
||||||
|
|
||||||
|
void loop() { |
||||||
|
if (available485()) Serial.println(get485message()); |
||||||
|
while (Serial.available()) { |
||||||
|
c = (char)Serial.read(); |
||||||
|
if (c == '\n') { |
||||||
|
send485(message.c_str()); |
||||||
|
message = ""; |
||||||
|
} else { |
||||||
|
message += c;
|
||||||
|
} |
||||||
|
}
|
||||||
|
} |
@ -0,0 +1,143 @@ |
|||||||
|
/*
|
||||||
|
* Demonstrates how to use Read Buttons in conjunction with SoftRS485: |
||||||
|
* |
||||||
|
* If a button is pressed, a corresponding flag is set. |
||||||
|
* The main loop checks for the state of those flags and |
||||||
|
* sends a message on the RS485 bus whenever a flag is set. |
||||||
|
*
|
||||||
|
* Additionally, the temperature is read from a DHT22 sensor once per minute |
||||||
|
*/ |
||||||
|
|
||||||
|
// include the library code:
|
||||||
|
#include <SoftRS485.h> |
||||||
|
#include <SimpleDHT.h> |
||||||
|
|
||||||
|
// 0=Test
|
||||||
|
// 1=Flur
|
||||||
|
// 2=Wohnzimmer
|
||||||
|
// 3=Bad EG
|
||||||
|
// 4=Treppenhaus
|
||||||
|
// 5=Arbeitszimmer
|
||||||
|
// 6=Bad OG
|
||||||
|
|
||||||
|
#define ID 0 |
||||||
|
#define HW_VERSION "2.1" |
||||||
|
#define PROGRAM "TempSender" |
||||||
|
#define SW_VERSION "1.5" |
||||||
|
|
||||||
|
#define BTN_INT 3 // button interrupt pin
|
||||||
|
#define Max485_RO 2 // read-output of Max485
|
||||||
|
#define Max485_RE 3 // not-read-enable of Max485
|
||||||
|
#define Max485_DE 8 // data enable of Max485
|
||||||
|
#define Max485_DI 9 // data input of Max485
|
||||||
|
|
||||||
|
#define TRESHOLD 1024 |
||||||
|
#define TRIGGER_LEVEL 200 |
||||||
|
|
||||||
|
#define DHT_PIN 4 |
||||||
|
#define PERIOD 100000000 // 100s
|
||||||
|
|
||||||
|
//#define DEBUG
|
||||||
|
//#define LOG_TO_SERIAL
|
||||||
|
#define SEND_485 |
||||||
|
|
||||||
|
boolean raw_states[8]; |
||||||
|
boolean states[8]; |
||||||
|
unsigned long capacitor[8]; |
||||||
|
unsigned long times[8]; |
||||||
|
unsigned long sensor_time = 0; |
||||||
|
|
||||||
|
// these values are used for temperature processing
|
||||||
|
SimpleDHT22 sensor(DHT_PIN); |
||||||
|
float temperature = 0; |
||||||
|
float humidity = 0; |
||||||
|
int err = SimpleDHTErrSuccess; |
||||||
|
|
||||||
|
void setup(){ |
||||||
|
for (int i=0; i<8;i++) { |
||||||
|
capacitor[i] = 0; |
||||||
|
raw_states[i] = LOW; |
||||||
|
states[i] = LOW; |
||||||
|
} |
||||||
|
Serial.begin(115200); |
||||||
|
init485(Max485_RO,Max485_RE,Max485_DE,Max485_DI); // library initialization:
|
||||||
|
pinMode(BTN_INT,INPUT_PULLUP); |
||||||
|
pinMode(14,INPUT_PULLUP); |
||||||
|
pinMode(15,INPUT_PULLUP); |
||||||
|
pinMode(16,INPUT_PULLUP); |
||||||
|
pinMode(17,INPUT_PULLUP); |
||||||
|
pinMode(18,INPUT_PULLUP); |
||||||
|
pinMode(19,INPUT_PULLUP); |
||||||
|
pinMode(20,INPUT_PULLUP); |
||||||
|
pinMode(21,INPUT_PULLUP); |
||||||
|
|
||||||
|
attachInterrupt(digitalPinToInterrupt(BTN_INT),isr,CHANGE); |
||||||
|
String s = "{nano:"+String(ID)+",hw:"+HW_VERSION+","+PROGRAM+":"+SW_VERSION+"}"; |
||||||
|
Serial.println(s); |
||||||
|
send485(s.c_str()); |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
Serial.println("14 15 16 17 18 19 20 21"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void isr(){ |
||||||
|
raw_states[0] = analogRead(14)<TRIGGER_LEVEL; |
||||||
|
raw_states[1] = analogRead(15)<TRIGGER_LEVEL; |
||||||
|
raw_states[2] = analogRead(16)<TRIGGER_LEVEL; |
||||||
|
raw_states[3] = analogRead(17)<TRIGGER_LEVEL; |
||||||
|
|
||||||
|
raw_states[4] = analogRead(18)<TRIGGER_LEVEL; |
||||||
|
raw_states[5] = analogRead(19)<TRIGGER_LEVEL; |
||||||
|
raw_states[6] = analogRead(20)<TRIGGER_LEVEL; |
||||||
|
raw_states[7] = analogRead(21)<TRIGGER_LEVEL; |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
for (int i=0;i<8;i++){ |
||||||
|
Serial.print(" ");
|
||||||
|
Serial.print(raw_states[i]); |
||||||
|
Serial.print(" "); |
||||||
|
} |
||||||
|
Serial.println(); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void send(int btn, long duration){ |
||||||
|
String s = "{nano:"+String(ID)+",btn:"+String(btn)+",ms:"+String(duration)+"}"; |
||||||
|
#ifdef SEND_485 |
||||||
|
for (int i = 0; i<10; i++){ |
||||||
|
if (send485(s.c_str())) break; |
||||||
|
Serial.println("collision detected, trying again:"); |
||||||
|
} |
||||||
|
#else |
||||||
|
Serial.println(s); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void loop(){ |
||||||
|
unsigned long now = micros(); |
||||||
|
for (int i=0;i<8;i++){ |
||||||
|
// we emulate a capacitor:
|
||||||
|
// when the button is pressed, it slowly loads, if the button is released, it unloads.
|
||||||
|
capacitor[i] = raw_states[i] ? capacitor[i]+1 : capacitor[i]>>1; |
||||||
|
|
||||||
|
// if the capacitor reaches a certain treshold, the state is changed
|
||||||
|
boolean new_state = capacitor[i]>TRESHOLD; |
||||||
|
|
||||||
|
// TODO: drop state after a maximum HIGH time
|
||||||
|
|
||||||
|
// when the state changes, the duration of the last state is calculated
|
||||||
|
if (states[i] != new_state){
|
||||||
|
long diff = (now - times[i])/1000; |
||||||
|
times[i] = now; |
||||||
|
if (states[i]) send(i+1,diff); // old state was HIGH → we are going LOW
|
||||||
|
states[i] = new_state; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (now - sensor_time > PERIOD){ |
||||||
|
sensor_time = now; |
||||||
|
if ((err = sensor.read2(&temperature, &humidity, NULL)) == SimpleDHTErrSuccess) { |
||||||
|
String s = "{nano:"+String(ID)+",temp:"+String(temperature,1)+",humi:"+String(humidity,1)+"}"; |
||||||
|
send485(s.c_str()); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,194 @@ |
|||||||
|
/*
|
||||||
|
* Demonstrates how to use Read Buttons in conjunction with SoftRS485: |
||||||
|
* |
||||||
|
* If a button is pressed, a corresponding flag is set. |
||||||
|
* The main loop checks for the state of those flags and |
||||||
|
* sends a message on the RS485 bus whenever a flag is set. |
||||||
|
*
|
||||||
|
* Additionally, the temperature is read from a DHT22 sensor once per minute |
||||||
|
*/ |
||||||
|
|
||||||
|
// include the library code:
|
||||||
|
#include <SoftRS485.h> |
||||||
|
#include <SimpleDHT.h> |
||||||
|
#include <TinyIRSender.hpp> |
||||||
|
|
||||||
|
// 0=Test
|
||||||
|
// 1=Flur
|
||||||
|
// 2=Wohnzimmer
|
||||||
|
// 3=Bad EG
|
||||||
|
// 4=Treppenhaus
|
||||||
|
// 5=Arbeitszimmer
|
||||||
|
// 6=Bad OG
|
||||||
|
|
||||||
|
#define ID 0 |
||||||
|
#define PROGRAM "Temp+IR" |
||||||
|
#define SW_VERSION "0.1" |
||||||
|
#define HW_VERSION "2.1" |
||||||
|
|
||||||
|
#define BTN_INT 3 // button interrupt pin
|
||||||
|
#define Max485_RO 2 // read-output of Max485
|
||||||
|
#define Max485_RE 3 // not-read-enable of Max485
|
||||||
|
#define Max485_DE 8 // data enable of Max485
|
||||||
|
#define Max485_DI 9 // data input of Max485
|
||||||
|
|
||||||
|
#define TRESHOLD 1024 |
||||||
|
#define TRIGGER_LEVEL 200 |
||||||
|
|
||||||
|
#define DHT_PIN 4 |
||||||
|
#define PERIOD 100000000 // 100s
|
||||||
|
|
||||||
|
#define IR_PIN 5 |
||||||
|
#define REPEATS 2 |
||||||
|
|
||||||
|
//#define DEBUG
|
||||||
|
//#define LOG_TO_SERIAL
|
||||||
|
#define SEND_485 |
||||||
|
|
||||||
|
boolean raw_states[8]; |
||||||
|
boolean states[8]; |
||||||
|
unsigned long capacitor[8]; |
||||||
|
unsigned long times[8]; |
||||||
|
unsigned long sensor_time = 0; |
||||||
|
|
||||||
|
// these values are used for temperature processing
|
||||||
|
SimpleDHT11 sensor(DHT_PIN); |
||||||
|
byte temperature = 0; |
||||||
|
byte humidity = 0; |
||||||
|
int err = SimpleDHTErrSuccess; |
||||||
|
|
||||||
|
// these constants are used for message parsing in handle(message)
|
||||||
|
const char* outer_delimiter = "{,}"; |
||||||
|
const char* inner_delimiter = ":"; |
||||||
|
|
||||||
|
void setup(){ |
||||||
|
for (int i=0; i<8;i++) { |
||||||
|
capacitor[i] = 0; |
||||||
|
raw_states[i] = LOW; |
||||||
|
states[i] = LOW; |
||||||
|
} |
||||||
|
Serial.begin(115200); |
||||||
|
init485(Max485_RO,Max485_RE,Max485_DE,Max485_DI); // library initialization:
|
||||||
|
pinMode(BTN_INT,INPUT_PULLUP); |
||||||
|
pinMode(14,INPUT_PULLUP); |
||||||
|
pinMode(15,INPUT_PULLUP); |
||||||
|
pinMode(16,INPUT_PULLUP); |
||||||
|
pinMode(17,INPUT_PULLUP); |
||||||
|
pinMode(18,INPUT_PULLUP); |
||||||
|
pinMode(19,INPUT_PULLUP); |
||||||
|
pinMode(20,INPUT_PULLUP); |
||||||
|
pinMode(21,INPUT_PULLUP); |
||||||
|
|
||||||
|
attachInterrupt(digitalPinToInterrupt(BTN_INT),isr,CHANGE); |
||||||
|
String s = "{nano:"+String(ID)+",hw:"+HW_VERSION+","+PROGRAM+":"+SW_VERSION+"}"; |
||||||
|
Serial.println(s); |
||||||
|
send485(s.c_str()); |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
Serial.println("14 15 16 17 18 19 20 21"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void isr(){ |
||||||
|
raw_states[0] = analogRead(14)<TRIGGER_LEVEL; |
||||||
|
raw_states[1] = analogRead(15)<TRIGGER_LEVEL; |
||||||
|
raw_states[2] = analogRead(16)<TRIGGER_LEVEL; |
||||||
|
raw_states[3] = analogRead(17)<TRIGGER_LEVEL; |
||||||
|
|
||||||
|
raw_states[4] = analogRead(18)<TRIGGER_LEVEL; |
||||||
|
raw_states[5] = analogRead(19)<TRIGGER_LEVEL; |
||||||
|
raw_states[6] = analogRead(20)<TRIGGER_LEVEL; |
||||||
|
raw_states[7] = analogRead(21)<TRIGGER_LEVEL; |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
for (int i=0;i<8;i++){ |
||||||
|
Serial.print(" ");
|
||||||
|
Serial.print(raw_states[i]); |
||||||
|
Serial.print(" "); |
||||||
|
} |
||||||
|
Serial.println(); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void send(int btn, long duration){ |
||||||
|
String s = "{nano:"+String(ID)+",btn:"+String(btn)+",ms:"+String(duration)+"}"; |
||||||
|
#ifdef SEND_485 |
||||||
|
for (int i = 0; i<10; i++){ |
||||||
|
if (send485(s.c_str())) break; |
||||||
|
Serial.println("collision detected, trying again:"); |
||||||
|
} |
||||||
|
#else |
||||||
|
Serial.println(s); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void handle(String message){ |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
Serial.println(message); |
||||||
|
#endif |
||||||
|
unsigned int ir_cmd = 0; |
||||||
|
unsigned int ir_addr = 0; |
||||||
|
unsigned int nano = 0; |
||||||
|
|
||||||
|
const char* outer_state = NULL; |
||||||
|
const char* inner_state = NULL;
|
||||||
|
char* token = strtok_r(message.c_str(), outer_delimiter, &outer_state); |
||||||
|
|
||||||
|
while (token != NULL) {
|
||||||
|
char* key = strtok_r(token,inner_delimiter,&inner_state); |
||||||
|
char* val = strtok_r(NULL,inner_delimiter,&inner_state); |
||||||
|
if (strcmp(key,"nano")==0) nano = atoi(val);
|
||||||
|
if (strcmp(key,"addr")==0) ir_addr = atoi(val); |
||||||
|
if (strcmp(key,"ir")==0) ir_cmd = atoi(val); |
||||||
|
token=strtok_r(NULL, outer_delimiter, &outer_state); |
||||||
|
} |
||||||
|
|
||||||
|
if (nano == ID){ // the message is addressed to us!
|
||||||
|
|
||||||
|
if (ir_addr && ir_cmd){ |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
Serial.print("Sending 0x"); |
||||||
|
Serial.print(ir_cmd,HEX); |
||||||
|
Serial.print(" to 0x"); |
||||||
|
Serial.println(ir_addr,HEX); |
||||||
|
#endif |
||||||
|
sendNECMinimal(IR_PIN, ir_addr, ir_cmd, REPEATS); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void loop(){ |
||||||
|
unsigned long now = micros(); |
||||||
|
for (int i=0;i<8;i++){ |
||||||
|
// we emulate a capacitor:
|
||||||
|
// when the button is pressed, it slowly loads, if the button is released, it unloads.
|
||||||
|
capacitor[i] = raw_states[i] ? capacitor[i]+1 : capacitor[i]>>1; |
||||||
|
|
||||||
|
// if the capacitor reaches a certain treshold, the state is changed
|
||||||
|
boolean new_state = capacitor[i]>TRESHOLD; |
||||||
|
|
||||||
|
// TODO: drop state after a maximum HIGH time
|
||||||
|
|
||||||
|
// when the state changes, the duration of the last state is calculated
|
||||||
|
if (states[i] != new_state){
|
||||||
|
long diff = (now - times[i])/1000; |
||||||
|
times[i] = now; |
||||||
|
if (states[i]) send(i+1,diff); // old state was HIGH → we are going LOW
|
||||||
|
states[i] = new_state; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (now - sensor_time > PERIOD){ |
||||||
|
sensor_time = now; |
||||||
|
if ((err = sensor.read(&temperature, &humidity, NULL)) == SimpleDHTErrSuccess) { |
||||||
|
String s = "{nano:"+String(ID)+",temp:"+String((int)temperature)+",humi:"+String((int)humidity)+"}"; |
||||||
|
#ifdef LOG_TO_SERIAL |
||||||
|
Serial.println(s); |
||||||
|
#endif |
||||||
|
send485(s.c_str()); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (available485()) handle(get485message()); |
||||||
|
} |
Loading…
Reference in new issue