/* * meteo4.c ... firmware for the open hardware meteostation based on ATmega128 clocked at 14.7456MHz * corresponds to PCB versions 1.3-1.6 meteo3.pro - meteo6.pro * supported sensors: SHT75, SMT160, MPX1114, VTP9812FH, wind sensors from WH1080 * * Copyright (C) 2010-2020 Jiri Pittner * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This program is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * You should have received a copy of the GNU General Public License * along with this program. If not, see . * * */ //corresponding hardware kicad schematics: meteo6.pro, meteo7.pro //device hardware options #define HAS_RFM22 #define NO_PRESSURE #define NO_SHT #define HAS_ANEMO_WH1080 #undef HAS_ANEMO_TX20 #define HAS_RAIN #undef PHOTODIODE #define SERIAL 5 /* #undef HAS_RFM22 #define NO_PRESSURE #define NO_SHT #define HAS_ANEMO_TX20 #undef HAS_ANEMO_WH1080 #define HAS_RAIN #define PHOTODIODE #define SERIAL 3 */ #define DEBUG //repeat transmition of each datagram to prevent loss #define TXCOUNT 4 #define DEVICE_TYPE M2_METEOSTATION #ifdef HAS_RFM22 //PORTB SPI #define SPIDI PB3 /*MISO*/ #define SPIDO PB2 /*MOSI*/ #define SPICLK PB1 /*SCK*/ #define SPICS PB0 /*CS*/ #define CSACTIVE cbi(PORTB,SPICS) #define CSPASSIVE sbi(PORTB,SPICS) #define RFM_TXEN PB7 /*used explicitly also in non-RFM version*/ #define RFM_SHDN PG2 #define RFM_CLK PG4 /*gpio1*/ #endif //NOTE: DS18B20 has a different pinout than SMT160!!! //NOTE: NOTE internal pullup is OK for very short cables, but, 3k9 or 4k7 pullup definitely needed for DS18B20 with longer cables //NOTE: with DS18B20 line protection requires diode clamps, SMBJ transils have too high capacity //PINOUT OF SENSORS OF WH1080: //wind speed wind cups - 2 middle pins of the RJ11, relay contact twice/360 degrees, 100nF debounce, connected to PE4 //wind direction weathervane - 2 inner pins go through; outer 2 pins of the 4-pin connector RJ11 connect angle-dependent resistance, //connected to PF4 and gnd and via 10k resistor to VCC5 a 10nF parallel PF4/gnd, ADC4 channel //rain sensor - relay on the two middle pins - connected to RAIN_GAUGE as usual with 100nF debounce //PINOUT: // //PA0-7 AUX and LED outputs optional //optional display //PC0-3=DB4-7 //PC4=E //PC5=RW //PC6=RS //PC7=light // //PB1,PE0,PE1,RESET ... in system programming port //PB7= 433 MHZ TX power //PB5=OC1A =433 MHZ modulation //PB4 anemo_CS //PB6 anemo signal // //PE5 rain gauge bucket signal INT5 //PE4 rotcoder_push / windspeed WH800 optional //PE6 rotcoder_left optional //PE3 rain gauge heater relay (optional) //PE7 rotcoder_right optional //PE2 smt160 output (optional) // //PF0 = ADC0 pressure sensor //PF1 = ADC1 pressure sensor reference for differential measurements (not used presently) //PF2 = ADC2 = gnd for differential mesuarement from ADC3 //PF3 = ADC3 = photodiode //PF7 ADC7 SMT2 output //PF6 ADC6 switch second range shunt for photodiode (highZ/GND) or input from photoresistor-deprecated //PF4 ADC4 sun sensor / WH1080 wind direction (optional) //PF5 =ADC5 input voltage 150k/33k divisor // //PD7 = SDA sht75_sda //PD6 = SCK sht75_sck //PD4 sht75_sda_pulldown transistor //PD5 sht75_power //PD2=UART1 RX //PD3=UART1 TX //PD1=rain_sensor optional //PD0=RX433 optional //PG3 = SMT160_2_PWR optional //calibration results //voltage stability has no direct impact on the meteorological measurements, //therefore no accurate reference is used; these two values are relevant only for checking the incoming voltage to the device //to detect possible power problems //UART speed for debugging #define BAUD 115200 #include "backward.h" #include #include #include #include #include #include #include #include #include #include #include #include "meteo2.h" #if defined(at90s2313) || defined(at90s8535) #else #define ATmega #endif #if (XTAL == 14745600L) #define oversampling 4 #else #define oversampling 2 #endif #ifndef MCU #define emulate #else #define AVR_assembler #endif #ifdef HAS_RFM22 //OOK 433 backward compatible to Aurel modules //receive parameter and fsk dev here unused uint32_t frequency=433920000UL; uint8_t modulation=1; uint8_t txpower=7; uint16_t fsk_dev=2500; uint32_t rxbw=150000; uint32_t datarate=5000; #endif watchdog(uint8_t onoff) { if(onoff) {wdt_enable(WDTO_2S); wdt_reset();} else {wdt_reset();wdt_disable();} } void bin2letter(char *c, uint8_t b) { *c = b<10? '0'+b : 'A'+b-10; } void bin2octet(char *octet, uint8_t bin) { bin2letter(octet,bin>>4); bin2letter(octet+1,bin&0x0f); } uint8_t letter2bin (char c) { return c>'9' ? c+10-(c>='a'?'a':'A') : c-'0'; } uint8_t octet2bin(char* octet) { return (letter2bin(octet[0])<<4) | letter2bin(octet[1]); } #define itoa10(N,S) itoa(N,S,10) #define itoa16(N,S) itoa(N,S,16) void printP (PGM_P string){ char c; c=pgm_read_byte(string); while (c) { loop_until_bit_is_set(UCSR1A, UDRE); UDR1 = c; c=pgm_read_byte(++string); } return; } void print (char *string){ while (*string) { loop_until_bit_is_set(UCSR1A, UDRE); UDR1 = *string++; } return; } //UART initialize #define UART_INIT(baud) { \ UBRR1H=0; \ UBRR1L= (XTAL/baud+15)/16-1; \ UCSR1B=(1< 140000UL) { dwn3_bypass=1; if(rxbw < 185000UL) { ndec_exp=1; if(rxbw < 160000UL) filset=4; else if(rxbw < 170000UL) filset=5; else filset=15; } else { ndec_exp=0; if(rxbw < 200000UL) filset=15; else { if(rxbw < 300000UL) filset = (rxbw-200000UL)/25000UL; else filset = 8+(rxbw-300000UL)/50000UL; if(filset>14) filset=14; } } } else { dwn3_bypass=0; uint16_t decimation = 150000UL/rxbw; ndec_exp=0; while(decimation>0) {++ndec_exp; decimation>>=1;} uint32_t tmp = rxbw << ndec_exp; if(tmp<70000UL) tmp=70000UL; filset = (tmp-60000UL)/10000UL; if(filset>7) filset=7; } if(modulation==1) //OOK { if(datarate<2000) ndec_exp=4; else if(datarate<3000) ndec_exp=3; else if(datarate<6000) ndec_exp=2; else ndec_exp=1; } rfm22_write(0x1C, (dwn3_bypass<<7)|(ndec_exp<<4)|filset); //printf("dwn3_bypass %d, ndec_exp %d, filset %d, 0x1c=%02x\n",dwn3_bypass,ndec_exp,filset, (dwn3_bypass<<7)|(ndec_exp<<4)|filset); //further RX parameters derived from bandwidth and data rate uint16_t rxosr,crgain; uint32_t ncoff; rxosr = 8*500000UL*(1+2*dwn3_bypass)/datarate; rxosr >>= ndec_exp; crgain = 2 + 65536UL/rxosr; { uint64_t tmp = datarate; tmp <<= 20+ndec_exp; ncoff = tmp/500000UL/(1+2*dwn3_bypass); } //printf("rxosr %d crgain %d ncoff %d \n",rxosr,crgain,ncoff); //printf("0x20-25: %02x %02x %02x %02x %02x %02x\n", rxosr&0xff,(((rxosr>>8)&7)<<5) | ((ncoff>>16)&0x0f),(ncoff>>8)&0xff,ncoff&0xff,(crgain>>8)&7,crgain&0xff); rfm22_write(0x20, rxosr&0xff); rfm22_write(0x21, (((rxosr>>8)&7)<<5) | ((ncoff>>16)&0x0f) ); rfm22_write(0x22, (ncoff>>8)&0xff); rfm22_write(0x23, ncoff&0xff); rfm22_write(0x24, (crgain>>8)&7); rfm22_write(0x25, crgain&0xff); //OOK parameters uint16_t ookcnt = 1500000UL/datarate; rfm22_write(0x2c, 0x38 | (ookcnt>>8)); rfm22_write(0x2d, ookcnt&0xff); rfm22_write(0x2e, 0x24); rfm22_write(0x30, 0x01); //Disable packet handling //rfm22_write(0x30, 0x88);//for packet //rfm22_write(0x08, 0x13);//for packet rfm22_write(0x34, 0x08); //4 byte preamble needed? rfm22_write(0x35, 0x20); //2 byte preamble detection needed? rfm22_write(0x69, 0x14); //AGC disable , set PGA gain rfm22_write(0x6a, 0xcf); //try also CF //AGC slow; other parameters accoring to RSSI erratum rfm22_write(0x6D, txpower); // TXpower { uint16_t tmp = datarate/1000; rfm22_write(0x6e, tmp>>8); rfm22_write(0x6f, tmp&0xff); } rfm22_write(0x70, 0x00); //no manchester //modulation fsk_dev /= 625; fsk_dev &= 0x1ff; uint8_t r71 = ((fsk_dev >>8)&1)<<2; r71 |= modulation; //packet fifo |0x20; rfm22_write(0x71, r71); rfm22_write(0x72, fsk_dev&0xff); //fsk frequency deviation low byte //set frequency rfm22_write(0x73, 0x00); // No frequency offset rfm22_write(0x74, 0x00); // No frequency offset uint8_t r75 = 0x40; if(freq>= 480000000UL) {r75 |= 0x20; freq >>= 1;} uint8_t fb = freq / 10000000UL -24; r75 |= fb; uint32_t fc = freq - (fb+24UL)*10000000UL; //0-10MHz remainder fc <<= 6; //*64 fc /= 10000; rfm22_write(0x75, r75); rfm22_write(0x76, (fc>>8)&0xff); rfm22_write(0x77, fc&0xff); rfm22_write(0x79, 0x00); // no frequency hopping channel rfm22_write(0x7A, 0x00); // no frequency hopping step rfm22_txon(0); //go to rx mode } #endif ///////////////////////////END RFM22 routines int32_t adcread(uint8_t mux, uint16_t nrep) { ADCSRA=1<0) //skip the first measurement after channel change to let it stabilize { if((mux&0x1f)>=8 && v>=512) v-=1024; //differential r += v; } } ADCSRA=0; //sbi(SREG,7); return r; } float vcc5(void) { //read the bandgap reference and compute Vcc of the ADC #if USE_BANDGAP //calibration constant #define VBANDGAP 1.23 uint32_t reference = adcread(30|(1<=512L*N_PRESSURE) r-= 1024L*N_PRESSURE; return (int32_t) 1000*(p0 - r/(0.009*1024.*N_PRESSURE*(mux==2?10.:200.))); } //CRC routines uint8_t crc8(uint8_t crc, uint8_t *data, uint16_t len, const uint8_t polynom) { for(; len>0; --len) { crc ^= *data++; uint8_t bit; for(bit=8; bit>0; --bit) { if(crc&0x80) crc = (crc<<1)^polynom; else crc <<=1; } } return crc; } uint8_t revbyte(uint8_t x)//reverse bit order { x= (x&0x55)<<1 | (x&0xaa)>>1; x= (x&0x33)<<2 | (x&0xcc)>>2; x= (x&0x0f)<<4 | (x&0xf0)>>4; return x; } #define POLY 0x8408 /* The crc16 routine has been downloaded from a public domain internet source 16 12 5 this is the CCITT CRC 16 polynomial X + X + X + 1. This works out to be 0x1021, but the way the algorithm works lets us use 0x8408 (the reverse of the bit pattern). The high bit is always assumed to be set, thus we only use 16 bits to represent the 17 bit value. */ uint16_t crc16(uint8_t *data_p, uint16_t length) { unsigned char i; unsigned int data; unsigned int crc = 0xffff; if (length == 0) return (~crc); do { for (i=0, data=(uint16_t)0xff & *data_p++; i < 8; i++, data >>= 1) { if ((crc & 0x0001) ^ (data & 0x0001)) crc = (crc >> 1) ^ POLY; else crc >>= 1; } } while (--length); crc = ~crc; data = crc; crc = (crc << 8) | (data >> 8 & 0xff); return (crc); } #undef POLY // temperature and humidity routines uint8_t shtcomm(uint8_t x, uint16_t *readout) { uint8_t data[4]; data[0]=x; int8_t i,j; TWCR=0; cbi(DDRD,PD7); //SDA sbi(PORTD,PD6);cbi(PORTD,PD4); sbi(DDRD,PD6); //SCL sbi(DDRD,PD4); //SDA pulldown delay_sht(); for(i=0; i<10; ++i) {cbi(PORTD,PD6);delay_sht();sbi(PORTD,PD6);delay_sht();} sbi(PORTD,PD4); //pull SDA LOW delay_sht(); cbi(PORTD,PD6); //scl low delay_sht(); sbi(PORTD,PD6); //scl high delay_sht(); cbi(PORTD,PD4); //sda high delay_sht(); cbi(PORTD,PD6); //scl low delay_sht();delay_sht();delay_sht(); for(i=7; i>=0; --i) { if(x&(1<=0; --i) { sbi(PORTD,PD6); //scl high delay_sht(); data[j] |= (PIND>>7)&1; //PD7 if(i) data[j]<<=1; cbi(PORTD,PD6); //scl low delay_sht(); } //generate Ack sbi(PORTD,PD4); //sda low delay_sht(); sbi(PORTD,PD6); //scl high delay_sht(); cbi(PORTD,PD6); //scl low delay_sht(); cbi(PORTD,PD4); //sda high } cbi(PORTD,PD6);cbi(PORTD,PD4); *readout= data[1]; *readout<<=8; *readout|= data[2]; //check CRC calculated from the command byte and two output bytes, assuming status register is the default 0 uint8_t crc=revbyte(crc8(0,data,3,0x31)); #if 0 char c[64]; sprintf(c,"CRC %x %x\n",crc,data[3]); print(c); #endif return crc-data[3]; //0 is OK } int16_t temperature(int16_t *h) //temperature in 0.01C { //power up sensor sbi(PORTD,PD5); sbi(DDRD,PD5); delay_ms(30); //wait for temperature sensor to stabilize int16_t t=M2_UNDEFINED_TEMP; *h=M2_UNDEFINED_HUMID; uint16_t readout; //read temperature if(shtcomm(3,&readout)) goto end; #if 0 printP(PSTR("temperature readout = 0x")); { char c[8]; itoa16(readout,c); print(c);print("\n"); } #endif //calibrate (cf. SHT75 datasheet) t = readout; t -= 4010; float temp=0.01*t; //read humidity if(shtcomm(5,&readout)) goto end; #if 0 printP(PSTR("humidity readout = 0x")); { char c[8]; itoa16(readout,c); print(c);print("\n"); } #endif //calibrate non-linearity of humidity sensor (cf. SHT75 datasheet) float hum = ((-1.5955e-6*readout)+0.0367)*readout-2.0468; //calibrate temperature dependence hum += (temp-25.)*(0.01+0.00008*readout); *h = (int16_t) (10.*hum); //power down sensor to prevent self-heating end: cbi(PORTD,PD5); return t; } //anemometer and rain gauge routines uint8_t heater=0; #ifdef HAS_ANEMO_WH1080 #define ANEMO_WH1080_RESISTOR 10000UL #define ANEMO_WH1080_NADC 32 #define ANEMO_WH1080_DISCONNECTED 100000UL static const uint32_t wh1080_resistances[16]={688,881,1000,1403,2200,3156,3920,6630,8270,14038,15800,21050,29800,36200,48500,66500}; static const uint8_t wh1080_directions[16]={5,3,4,7,6,9,8,1,2,11,10,15,0,13,14,12}; //determine instantaneous direction in 1/16 of 2pi uint8_t wh1080_direction(uint8_t *dir) { int32_t adc=adcread(4, ANEMO_WH1080_NADC); int32_t r = (adc*ANEMO_WH1080_RESISTOR)/(ANEMO_WH1080_NADC*1024UL-adc); #ifdef DEBUG { char c[64]; sprintf(c,"anemo adc %ld resistor %ld\n",adc,r); print(c); } #endif if(r>ANEMO_WH1080_DISCONNECTED) return 0; //find direction uint8_t i; for(i=0; i<15; ++i) { if(r<(wh1080_resistances[i]+wh1080_resistances[i+1])/2) {*dir=wh1080_directions[i]; return 1;} } *dir=wh1080_directions[15]; return 1; } //count pulses at most 5 seconds or 10 pulses #define ANEMO_WH1080_MAX_INTERVAL 5000 #define ANEMO_WH1080_MAX_PULSES 5 #define COUNTER3TOP ((uint16_t)(XTAL/1000+.5)) #define ANEMO_WH1080_HZ_TO_MS 0.66 #define ANEMO_WH1080_UNPHYSICAL 500 static volatile uint8_t pulses=0; static volatile uint16_t current_speed=0; //in 0.1 m/s static volatile uint16_t current_gusts=0; //in 0.1 m/s static volatile uint16_t counter3=0; //millisecond counter static volatile uint16_t counter3last=0; static volatile uint16_t tcnt3last=0; void process_wh1080(uint8_t waspulse) { if(waspulse) { ++pulses; //compute gust speed uint16_t gusts=10000/(counter3-counter3last)*ANEMO_WH1080_HZ_TO_MS; //0.1Hz to 0.1 m/s if(gusts>current_gusts && gusts=ANEMO_WH1080_MAX_INTERVAL || pulses >= ANEMO_WH1080_MAX_PULSES) { uint16_t interval= counter3; //in system clock ticks cbi(SREG,7); uint32_t npulses=pulses; pulses=0; TCNT3=0; tcnt3last=0; counter3=counter3last=0; sbi(SREG,7); current_speed= (10*1000*ANEMO_WH1080_HZ_TO_MS)*npulses/interval; current_gusts=current_speed; } } //interrupt for the wind cup rotation (2 pulses per 360 degrees) INTERRUPT(SIG_INTERRUPT4) //set as falling edge interrupt { if(bit_is_clear(PINE,PE4)) //check that we are after the falling edge { if(counter3-counter3last<=1) return; //debounce sub-1ms intervals process_wh1080(1); } return; } INTERRUPT(SIG_OUTPUT_COMPARE3A) { ++counter3; if(counter3>=ANEMO_WH1080_MAX_INTERVAL) process_wh1080(0); } //return 1 on success uint8_t anemo_reset_wh1080(void) { //for ADC4 cbi(PORTF,PF4); cbi(DDRF,PF4); //read direction, 0xff indicated disconnected device uint8_t dir; uint8_t r=wh1080_direction(&dir); if(r==0) return 0; //use timer3 TCNT3=0; TCCR3A=0; TCCR3C=0; OCR3A= COUNTER3TOP; TCCR3B= (1<0; --l) if(bit_is_clear(PINB,PB6)) goto active; } return 9; active:; } watchdog(1); DELAY_HALF; for(i=0; i<41; ++i) { if(bit_is_set(PINB,PB6)) *msg |= (1LL<=5 && i%4 == 1) print(" "); print((raw>>i)&1?"1":"0");} printP(PSTR("\n"));} #endif if((raw&0x1fLL)!=4) return 1; //error raw>>=5; //header *dir = check = raw&0x0fLL; raw>>=4; *speed = raw&0x0fffLL; raw>>=4; raw>>=4; raw>>=4; uint8_t checksum = raw&0x0fLL; uint8_t mycheck = *dir + *speed + (*speed>>4) + (*speed>>8); mycheck &= 15; if(checksum!=mycheck) return 3; raw>>=4; uint8_t invdir = raw&0x0fLL; raw>>=4; uint16_t invs = raw&0x0fffLL; if(*dir != (invdir^0x0f)) return 2; if((invs^0x0fff) != *speed) return 4; if(*speed >= 2048) return 5; //unphysical #if 1 char c[8]; printP(PSTR("Direction = ")); itoa10(*dir,c);print(c); printP(PSTR(" Speed = ")); itoa10(*speed,c);print(c); printP(PSTR("\n")); #endif return 0; } #endif //HAS_ANEMO_TX20 #define TEMPPORT PINE #define TEMPPORTOUT PORTE #define TEMPPORTDDR DDRE #define TEMPPIN PE2 uint8_t check_thermo_smt() { cbi(TEMPPORTDDR,TEMPPIN); sbi(TEMPPORTOUT,TEMPPIN); //pullup to prevent random noise uint8_t i,last,l; watchdog(1); delay_ms(30); //let the parasitic capacity charge last= bit_is_set(TEMPPORT,TEMPPIN); for(i=0; i<100; ++i) { delay_xs(XTAL/8000); if((l=bit_is_set(TEMPPORT,TEMPPIN))^last) {cbi(TEMPPORTOUT,TEMPPIN); return 1;} last=l; } cbi(TEMPPORTOUT,TEMPPIN); return 0; } //SMT160 temperature in rain gauge int16_t temperature_smt0(void) // thermometer returns in 0.005 C { int16_t t; uint8_t i; uint16_t lcount,hcount; watchdog(1); //maybe it sometimes hangs here??? //SMT160-30 duty=0.320+0.00470*T, T=(duty-0.32)/0.00470 lcount=hcount=0; //interrupts have not been disabled intentionally, catching a rain bucket has a higher priority than the accuracy of temperature { uint8_t i; for(i= #if (XTAL == 3686400L) 0 #else #if (XTAL == 14745600L) 64 #else 128 #endif #endif ; --i;) { //optimized compilation results in irreproducible and wrong timings, therefore inline assembly asm volatile ( //loop_until_bit_is_set(TEMPPORT,TEMPPIN); "TEMP1:\n\t" "sbis %4,%5" "\n\t" "rjmp TEMP1" "\n\t" //loop_until_bit_is_clear(TEMPPORT,TEMPPIN); "TEMP2:\n\t" "sbic %4,%5" "\n\t" "rjmp TEMP2" "\n\t" //while(bit_is_clear(TEMPPORT,TEMPPIN)) ++lcount; "TEMP3:\n\t" "adiw %1,1" "\n\t" "sbis %4,%5" "\n\t" "rjmp TEMP3" "\n\t" //while(bit_is_set(TEMPPORT,TEMPPIN)) ++hcount; "TEMP4:\n\t" "adiw %0,1" "\n\t" "sbic %4,%5" "\n\t" "rjmp TEMP4" "\n\t" //parameter lists : "=w" (hcount), "=w" (lcount) //outputs : "0" (hcount), "1" (lcount), "M" ((uint8_t) &(TEMPPORT) - 0x20), "I" (TEMPPIN) //inputs : "cc" //clobber ); } } #if 0 { uint32_t x; x=10000; x*=hcount; x /=((uint32_t)hcount+lcount); char c[8]; itoa10(x,c); printP(PSTR("10000*Duty=")); print(c); printP(PSTR("\n")); } #endif uint32_t x; x=68085L; x*=hcount; x /=((uint32_t)hcount+lcount); x*=10; int32_t y = x-217870; y>>= 4; return (int16_t) y; } #define TEMPPORT2 PINF #define TEMPPORTOUT2 PORTF #define TEMPPORTDDR2 DDRF #define TEMPPIN2 PF7 uint8_t check_thermo2_smt() { //power the chip sbi(DDRG,PG3); sbi(PORTG,PG3); cbi(TEMPPORTDDR2,TEMPPIN2); sbi(TEMPPORTOUT2,TEMPPIN2); //pullup to prevent random noise delay_ms(30); //let the parasitic capacity charge uint8_t i,last,l; watchdog(1); last= bit_is_set(TEMPPORT2,TEMPPIN2); for(i=0; i<100; ++i) { delay_xs(XTAL/8000); if((l=bit_is_set(TEMPPORT2,TEMPPIN2))^last) {cbi(TEMPPORTOUT2,TEMPPIN2); return 1;} last=l; } cbi(TEMPPORTOUT2,TEMPPIN2); cbi(DDRG,PG3);//prevent selfheating return 0; } //second SMT160 int16_t temperature2_smt0(void) // thermometer returns in 0.005 C { int16_t t; uint8_t i; uint16_t lcount,hcount; watchdog(1); //maybe it sometimes hangs here??? //SMT160-30 duty=0.320+0.00470*T, T=(duty-0.32)/0.00470 lcount=hcount=0; //interrupts have not been disabled intentionally, catching a rain bucket has a higher priority than the accuracy of temperature { uint8_t i; for(i= #if (XTAL == 3686400L) 0 #else #if (XTAL == 14745600L) 64 #else 128 #endif #endif ; --i;) { //optimized compilation results in irreproducible and wrong timings, therefore inline assembly asm volatile ( //loop_until_bit_is_set(TEMPPORT2,TEMPPIN2); "TEMP21:\n\t" "sbis %4,%5" "\n\t" "rjmp TEMP21" "\n\t" //loop_until_bit_is_clear(TEMPPORT2,TEMPPIN2); "TEMP22:\n\t" "sbic %4,%5" "\n\t" "rjmp TEMP22" "\n\t" //while(bit_is_clear(TEMPPORT2,TEMPPIN2)) ++lcount; "TEMP23:\n\t" "adiw %1,1" "\n\t" "sbis %4,%5" "\n\t" "rjmp TEMP23" "\n\t" //while(bit_is_set(TEMPPORT2,TEMPPIN2)) ++hcount; "TEMP24:\n\t" "adiw %0,1" "\n\t" "sbic %4,%5" "\n\t" "rjmp TEMP24" "\n\t" //parameter lists : "=w" (hcount), "=w" (lcount) //outputs : "0" (hcount), "1" (lcount), "M" ((uint8_t) &(TEMPPORT2) - 0x20), "I" (TEMPPIN2) //inputs : "cc" //clobber ); } } #if 0 { uint32_t x; x=10000; x*=hcount; x /=((uint32_t)hcount+lcount); char c[8]; itoa10(x,c); printP(PSTR("TEMP2 10000*Duty=")); print(c); printP(PSTR("\n")); } #endif uint32_t x; x=68085L; x*=hcount; x /=((uint32_t)hcount+lcount); x*=10; int32_t y = x-217870; y>>= 4; return (int16_t) y; } #define NREP_SMT_LOG 5 int16_t temperature_smt(uint8_t which) //in 0.01C { uint8_t i; int32_t t=0; watchdog(1); if(which) { sbi(DDRG,PG3); sbi(PORTG,PG3); delay_ms(50); } for(i=0; i<(1<>= 1+NREP_SMT_LOG; if(which) cbi(PORTG,PG3); //prevent self-heating return t; } //DS18B20 alternative temperature routines //adapted from the code of Davide Gironi, using internal pullup /* ds18b20 lib 0x02 copyright (c) Davide Gironi, 2012 Released under GPLv3. Please refer to LICENSE file for licensing information. References: + Using DS18B20 digital temperature sensor on AVR microcontrollers by Gerard Marull Paretas, 2007 http://teslabs.com/openplayer/docs/docs/other/ds18b20_pre1.pdf */ //connection #define DS18B20_PORT TEMPPORTOUT #define DS18B20_DDR TEMPPORTDDR #define DS18B20_PIN TEMPPORT #define DS18B20_DQ TEMPPIN #define DS18B20_PORT2 TEMPPORTOUT2 #define DS18B20_DDR2 TEMPPORTDDR2 #define DS18B20_PIN2 TEMPPORT2 #define DS18B20_DQ2 TEMPPIN2 //commands #define DS18B20_CMD_CONVERTTEMP 0x44 #define DS18B20_CMD_RSCRATCHPAD 0xbe #define DS18B20_CMD_WSCRATCHPAD 0x4e #define DS18B20_CMD_CPYSCRATCHPAD 0x48 #define DS18B20_CMD_RECEEPROM 0xb8 #define DS18B20_CMD_RPWRSUPPLY 0xb4 #define DS18B20_CMD_SEARCHROM 0xf0 #define DS18B20_CMD_READROM 0x33 #define DS18B20_CMD_MATCHROM 0x55 #define DS18B20_CMD_SKIPROM 0xcc #define DS18B20_CMD_ALARMSEARCH 0xec //timing #define DS18B20_DELAY_1 1 #define DS18B20_DELAY_14 14 #define DS18B20_DELAY_45 45 #define DS18B20_DELAY_60 60 #define _delay_us(us) delay_xs((XTAL/1000)*(us)/4/1000); //if more accuracy is needed, use other routine with inline __attribute__((gnu_inline)) /* * ds18b20 init */ uint8_t ds18b20_reset(uint8_t which) { uint8_t i; watchdog(1); if(which) { sbi(DDRG,PG3); sbi(PORTG,PG3); delay_ms(50); } if(which) { //low for 480us DS18B20_PORT2 &= ~ (1<>= 1; } } /* * read one byte */ uint8_t ds18b20_readbyte(uint8_t which){ uint8_t i=8, n=0; while(i--){ n >>= 1; n |= (ds18b20_readbit(which)<<7); } return n; } uint8_t ds_crc8(uint8_t crc, uint8_t *data, uint16_t len) { while(len--) { uint8_t inbyte = *data++; uint8_t i; for (i = 8; i; i--) { uint8_t mix = (crc ^ inbyte) & 0x01; crc >>= 1; if (mix) crc ^= 0x8C; inbyte >>= 1; } } return crc; } void printmsg(uint8_t *msg, uint8_t len) { printP(PSTR("DS: ")); char c[4]; bin2octet(c,len); c[2]=0; print(c); printP(PSTR(" ")); uint8_t i; for(i=0; i<(len+7)>>3; ++i) { bin2octet(c,msg[i]); c[2]=0; print(c); } printP(PSTR("\n")); } /* * get temperature in 1/16 C (12bit mode) */ int16_t ds18b20_gettemp(uint8_t which) { uint8_t data[9]; uint8_t i; int16_t retd = 0; uint8_t ds_present = ! ds18b20_reset(which); //reset if(!ds_present) printP(PSTR("thermometer not found in ds18b20_gettemp\n")); if(!ds_present) return M2_UNDEFINED_TEMP; cli(); ds18b20_writebyte(which,DS18B20_CMD_SKIPROM); //skip ROM ds18b20_writebyte(which,DS18B20_CMD_CONVERTTEMP); //start temperature conversion //avoid forbidden interrupts for a long time //wait until conversion is complete for(i=0; i<10; ++i) { watchdog(1); sei(); delay_ms(100); cli(); if(ds18b20_readbit(which)) goto conversion_done; } sei(); if(which) printP(PSTR("thermometer 2 ")); else printP(PSTR("r.g. thermometer ")); printP(PSTR("ds18b20 timeout\n")); return M2_UNDEFINED_TEMP; //timeout conversion_done: cli(); ds18b20_reset(which); //reset ds18b20_writebyte(which,DS18B20_CMD_SKIPROM); //skip ROM ds18b20_writebyte(which,DS18B20_CMD_RSCRATCHPAD); //read scratchpad //read scratchpad including crc for(i=0; i<=8; ++i) data[i] = ds18b20_readbyte(which); sei(); //debug printmsg(data,64); uint8_t crc=ds_crc8(0,data,8); if(crc!=data[8]) { char z[16]; itoa16(crc,z); printP(PSTR("crc our ")); print(z); printP(PSTR("\n")); itoa16(data[8],z); printP(PSTR("crc DS ")); print(z); printP(PSTR("\n")); return M2_UNDEFINED_TEMP; } //convert the 12 bit value obtained retd = data[1]; retd <<= 8; retd |= data[0]; return retd; } //DS18B20 todo: explicitly configure for the 12bit mode, select from more sensors //returns value in 0.01C averaged from two values int16_t temperature_ds(uint8_t which) { if(which) { //power the chip sbi(DDRG,PG3); sbi(PORTG,PG3); delay_ms(50); } int16_t t=ds18b20_gettemp(which); int16_t t2=ds18b20_gettemp(which); if(which) { //power off the chip cbi(PORTG,PG3); cbi(DDRG,PG3); } if(t==M2_UNDEFINED_TEMP) return M2_UNDEFINED_TEMP; if(t2==M2_UNDEFINED_TEMP) return M2_UNDEFINED_TEMP; t += t2; t *= 25; t /= 8; return t; } uint8_t thermo_present,smt_present; uint8_t thermo2_present,smt2_present; int16_t temperature_smtds(uint8_t which) //in 0.01C { if(which) { if(!thermo2_present) return M2_UNDEFINED_TEMP; if(smt2_present) return temperature_smt(1); return temperature_ds(1); } else { if(!thermo_present) return M2_UNDEFINED_TEMP; if(smt_present) return temperature_smt(0); return temperature_ds(0); } } //rain gauge interrupt static volatile uint8_t nbuckets =0; static volatile uint32_t counter2 =0; #ifdef HAS_RAIN INTERRUPT(SIG_INTERRUPT5) //set as falling edge interrupt { #if (XTAL >= 14745600L) if(counter2<50) return; #else if(counter2<25) return; //too short time since last bucket - software debounce #endif UDR1='I'; if(bit_is_clear(PINE,PE5)) { UDR1='R'; ++nbuckets; //check the bit a few cycles after the edge interrupt to avoid spurious ultrashort impulses TCNT2=0; counter2=0; } else UDR1='?'; //indicate spurious edge return; } #endif INTERRUPT(SIG_OVERFLOW2) { ++counter2; } // wireless communication routines //for testing the RF amplifier void txcw(void) { #ifdef HAS_RFM22 rfm22_txon(1); #endif sbi(DDRB,PB5); sbi(DDRB,PB7); sbi(PORTB,PB5); sbi(PORTB,PB7); uint8_t i; for(i=0; i<60; ++i) {watchdog(1); delay_ms(1000);} #ifdef HAS_RFM22 rfm22_txon(0); #endif cbi(PORTB,PB5); cbi(PORTB,PB7); } //transmit routines volatile uint8_t outcode[sizeof(METEO2_DATAGRAM)]; volatile uint8_t outcodelen=0; //0 indicates ready to receive, non-zero indicates ready to read it in main volatile uint8_t waittime=0; volatile uint8_t txcount=0; //repeat several times volatile static uint8_t obitcount=0, obytecount=0; //working counters typedef enum {init,oupmark,downmark,data,trailer,wait} OSTATE; static OSTATE ostate=init; static uint8_t ocount=0; //modulation like in keeloq remote controls void txcar(void) { switch (ostate) { case wait: if(--waittime) return; case init: //the user has just written the request to transmit //check maxcodelen ocount=13; ostate=oupmark; cbi(TIMSK,TOIE1); ICR1=(uint16_t)(XTAL*8./10000+.5)-1; OCR1A=((uint16_t)(XTAL*4./10000+.5)-1); TCNT1=0; cbi(TCCR1A,COM1A0); cbi(TCCR1A,COM1A1); sbi(TIMSK,TOIE1); sbi(TIMSK,OCIE1A); break; case oupmark: if(--ocount) {sbi(PORTB,PB5); return;} cbi(PORTB,PB5); cbi(TIMSK,TOIE1); TCNT1=0; ICR1=(uint16_t)(XTAL*6.1/10000+.5)-1; sbi(TIMSK,TOIE1); ostate=downmark; ocount=2; break; case downmark: if(--ocount) return; obitcount=obytecount=0; ostate=data; cbi(TIMSK,TOIE1); ICR1=(uint16_t)(XTAL*12./10000+.5)-1; sbi(TIMSK,TOIE1); break; case data: { uint8_t n; n=obitcount+(obytecount<<3); if(n>outcodelen+1) { //data finished cbi(PORTB,PB5); cbi(TIMSK,OCIE1A); ostate=trailer; ocount=13; OCR1A=0; } else { if(n) sbi(PORTB,PB5); //avoid spurious first peak if(n>outcodelen) { OCR1A=((uint16_t)(XTAL*12./10000+.5)-1)*1/3; ++obitcount; } else { OCR1A=((uint16_t)(XTAL*12./10000+.5)-1)* ((outcode[obytecount]& (1<counter= ++counter; #endif //compute CRC msg->crc = crc16((void *)msg,sizeof(METEO2_DATAGRAM)-2); //little endian assumed here as well as on the receiver //wait for end of previous transmit or switch on transmitter if(txcount || outcodelen) while(txcount || outcodelen) {delay_ms(10); watchdog(1);} else do_transmit(1); watchdog(1); delay_ms(50); //stabilize transmitter //transmit the code a few times memcpy(outcode,msg,sizeof(METEO2_DATAGRAM)); txcount=count; outcodelen=sizeof(METEO2_DATAGRAM)*8; //leave the receiver enough time to process individual packets watchdog(1); delay_ms(1000); watchdog(1); delay_ms(1000); watchdog(1); delay_ms(1000); } void txping(void) { METEO2_DATAGRAM msg; msg.device_type=M2_METEOSTATION; msg.serial=SERIAL; msg.report_type=M2_PING; uint16_t i; for(i=0; i<1024; ++i) { msg.arg2= i; transmit(&msg,TXCOUNT); } } //////////////////////////////////////////////////////// //rain gauge heater on/off thresholds in 0.01C static int16_t hyst_on __attribute__ ((section(".eeprom"))) = 350; static int16_t hyst_off __attribute__ ((section(".eeprom"))) = 450; //averaging definitions #define N_AVER_PRESSURE 64 #define N_AVER_LIGHT 128 #ifdef HAS_ANEMO_WH1080 #define N_AVER_WIND 16 #endif #ifdef HAS_ANEMO_TX20 #define N_AVER_WIND 64 #endif //contains calibration constants // //has to be big to get rid of AC noise #define N_LIGHT 4096 float v_light(void) { watchdog(1); //measure voltage at the diode //first roughly to determine gain #define CAL0 1.03 float v= CAL0* 2.56/1024*adcread(3|(1<0.2) { range=1; sbi(DDRF,PF6); delay_ms(20); v=v_light(); } #if 0 { char c[32]; sprintf(c,"Range %d Vlight=%.3fmV\n",range,v*1000); print(c); } #endif //compute the illuminance current #define kboltz 1.38065812e-23 #define elcharge 1.6021773349e-19 //this is calculated from datasheet of VTP9812FH from 100fc 25c short current and open voltage #define i0 1.1738e-13 float x=i0 * (expf(elcharge*v/kboltz/(celsius+273.15))-1.); float i= v/shunt[range] + x; //convert current to footcandles according to datasheet float fc; if(i<0.1e-6) fc=1e7*i/0.095; else fc=1e8*i; float lux=fc*10.764; { char c[64]; #if 0 sprintf(c,"exp=%.3guA Ilight=%.3fuA ",x*1e6,i*1e6); print(c); #endif sprintf(c,"Phi=%g lux\n",lux); print(c); } cbi(DDRF,PF6);//shunt OFF return lux; } main() { cbi(PORTE,PE3); sbi(DDRE,PE3); heater=0; sbi(SREG,7); UART_INIT(BAUD); {char dummy=UDR1;} sbi(UCSR1B,RXCIE); delay_ms(1); printP(PSTR("Reset!\n")); //check endianity { union {int i; char z[sizeof(int)];} u; u.i=1; if(u.z[0]!=1) printP(PSTR("Something is wrong, AVR/GCC should be little endian - swap bytes in transmit()!\n")); } #ifdef HAS_RFM22 rfm22_init(1,frequency,txpower,modulation,fsk_dev,rxbw,datarate); #endif do_transmit(0); //check presence of anemometer uint8_t anemo_present=0; #ifdef HAS_ANEMO_TX20 anemo_reset_tx20(); anemo_present = check_anemo(); #endif #ifdef HAS_ANEMO_WH1080 anemo_present = anemo_reset_wh1080(); #endif if(!anemo_present) printP(PSTR("NO ")); printP(PSTR("anemometer found\n")); //check presence of thermometer in the rain gauge smt_present = check_thermo_smt(); if(!smt_present) printP(PSTR("NO ")); printP(PSTR("r.g. SMT160 thermometer found\n")); if(smt_present) thermo_present=1; else { thermo_present= ! ds18b20_reset(0); if(!thermo_present) printP(PSTR("NO ")); printP(PSTR("r.g. DS18B20 thermometer found\n")); } smt2_present = check_thermo2_smt(); if(!smt2_present) printP(PSTR("NO ")); printP(PSTR("SMT160 thermometer2 found\n")); if(smt2_present) thermo2_present=1; else { thermo2_present= ! ds18b20_reset(1); if(!thermo2_present) printP(PSTR("NO ")); printP(PSTR("DS18B20 thermometer2 found\n")); } //start timer2 TCNT2=0; TCCR2=5; //CK1024 sbi(TIMSK,TOIE2); //overflow interrupts //start raing gauge interrupt INT5, no pullup #ifdef HAS_RAIN { cbi(DDRE,PE5); cbi(PORTE,PE5); delay_ms(10); sbi(EICRB,ISC51); cbi(EICRB,ISC50); sbi(EIMSK,INT5); //falling edge } #endif METEO2_DATAGRAM msg; msg.device_type=M2_METEOSTATION; msg.serial=SERIAL; //transmit reset report msg.report_type=M2_RESET; msg.arg1= anemo_present; msg.arg2= thermo_present; transmit(&msg,TXCOUNT); //variables to detect changes int16_t tempold= M2_UNDEFINED_TEMP; int16_t temprainold= M2_UNDEFINED_TEMP; int16_t humidold= M2_UNDEFINED_HUMID; int32_t oldpressure= M2_UNDEFINED_PRESSURE; int32_t oldohms= 0; int32_t sumpressure = 0; uint16_t npressure=0; uint16_t nlight=0; #ifdef PHOTODIODE float sumlux=0.; #else //deprecated #define R_PHOTO1_GND 9987. int32_t sumlight=0; #endif volatile uint8_t nrain; uint8_t heater_count=0; uint8_t dirmax=0; uint16_t speedmax=0; float sumspeedx=0., sumspeedy=0.; uint16_t nanemo=0; uint16_t voltsold=0; //count problems with anemometer #ifdef HAS_ANEMO_TX20 uint16_t nbad=0; #endif uint16_t pass=0; uint16_t rainpass=0; printP(PSTR("Entering main loop\n")); while(1) { ++pass; ++rainpass; //wait for end of transmit and switch off transmitter then while(txcount || outcodelen) { watchdog(1); delay_ms(10); } do_transmit(0); watchdog(1); //process commands from UART if(inuart[inuartlen-1]== '\n'||inuart[inuartlen-1]=='\r') { inuart[inuartlen]=0; inuart[inuartlen-1] = '\n'; print(inuart); //execute the command switch(inuart[0]) { case 'h': { if(strncmp(inuart,"high=",5)) break; int16_t t; char c[8]; t=atoi(inuart+5); itoa10(t,c); printP(PSTR("HYST_OFF set to ")); print(c); printP(PSTR("\n")); eeprom_write_word(&hyst_off,t); } break; case 'l': { if(strncmp(inuart,"low=",4)) break; int16_t t; char c[8]; t=atoi(inuart+4); itoa10(t,c); printP(PSTR("HYST_ON set to ")); print(c); printP(PSTR("\n")); eeprom_write_word(&hyst_on,t); } break; case 'T': printP(PSTR("testing transmitter by CW\n")); txcw(); break; case 'P': printP(PSTR("testing transmitter by PING\n")); txping(); break; #ifdef HAS_RFM22 case 'B': //set datarate datarate=atoi10_32(inuart+1); goto rfm22_setup; case 'b': //set rxbw rxbw=atoi10_32(inuart+1); goto rfm22_setup; case 'F': //set fsk_dev fsk_dev=atoi(inuart+1); goto rfm22_setup; case 'm': //set modulation modulation=atoi(inuart+1); goto rfm22_setup; case 'f': //set frequency in hz frequency=atoi10_32(inuart+1); { char z[32]; sprintf(z,"f=%ld\n",frequency); print(z); } rfm22_setup: watchdog(1); rfm22_init(0,frequency,txpower,modulation,fsk_dev,rxbw,datarate); printP(PSTR("rfm22 set\n")); break; case 'r': { uint8_t addr, data; addr=octet2bin(inuart+1); data = rfm22_read(addr); char z[3]; bin2octet(z, data); z[2]='\n'; z[3]=0; printP(PSTR("\n"));print(z); } break; case 'w': //Wxx xx { uint8_t addr, data; addr=octet2bin(inuart+1); data=octet2bin(inuart+4); rfm22_write(addr,data); printP(PSTR("done\n")); } break; #endif default: printP(PSTR("Unknown command: "));; print(inuart); break; } //flush buffer and allow uart receive again cbi(UCSR1B,RXCIE); inuartlen=0; sbi(UCSR1B,RXCIE); watchdog(1); } //perform measurements char c[128]; watchdog(1); int16_t temp; int16_t humid; #ifndef NO_SHT temp=temperature(&humid); #else temp= thermo2_present? temperature_smtds(1) : M2_UNDEFINED_TEMP; humid=M2_UNDEFINED_HUMID; #endif watchdog(1); delay_ms(500); int16_t temprain; if(thermo_present) temprain =temperature_smtds(0); else temprain = M2_UNDEFINED_TEMP; int32_t pressure; #ifndef NO_PRESSURE pressure =getpressure(0); sprintf(c,"P=%ldPa\n",pressure); print(c); #else pressure = M2_UNDEFINED_PRESSURE; #endif #ifdef PHOTODIODE //new version float lux= light(temp==M2_UNDEFINED_TEMP?25.:0.01*temp); #else //deprecated uint32_t light= adcread(6|(1<=15 || (temp-tempold)<=-15 || (humid-humidold)>=15|| (humid-humidold)<=-15) || (pass&0x3f)==0) //report every 5 minutes or when change { msg.device_type=M2_METEOSTATION; msg.serial=SERIAL; msg.report_type=M2_TEMP_HUMID; msg.arg2=humid; msg.arg3=temp; transmit(&msg,TXCOUNT); tempold=temp; humidold=humid; printP(PSTR("transmit temperature\n")); } } //pressure sensor if(pressure!=M2_UNDEFINED_PRESSURE) {++npressure; sumpressure += pressure;} if(npressure == N_AVER_PRESSURE) { pressure = sumpressure/N_AVER_PRESSURE; npressure=0; sumpressure=0; sprintf(c,"P= %.2fhPa\n",pressure*0.01); print(c); { msg.report_type=M2_PRESSURE; msg.arg1= humid==M2_UNDEFINED_HUMID?0:humid/10; msg.arg2=temp; msg.arg3=pressure; transmit(&msg,TXCOUNT); oldpressure=pressure; printP(PSTR("transmit pressure\n")); } } //light - report ohms of the photoresistor ++nlight; #ifdef PHOTODIODE sumlux += lux; #else sumlight += light; #endif if(nlight == N_AVER_LIGHT) { #ifdef PHOTODIODE float luxes=sumlux/nlight; sumlux=0.; nlight=0; msg.report_type=M2_LUX; if(sizeof(uint32_t) == sizeof(float)) //just for sure { memcpy(&msg.arg3,&luxes,sizeof(uint32_t)); //raw IEEE float is transmitted transmit(&msg,TXCOUNT); printP(PSTR("transmit lux\n")); } #else //deprecated float ohms = 1024.*R_PHOTO1_GND*N_LIGHT*N_AVER_LIGHT/sumlight - R_PHOTO1_GND; sprintf(c,"R = %g ohms\n",ohms); print(c); sumlight=0; nlight=0; msg.report_type=M2_LIGHT; if(sizeof(uint32_t) == sizeof(float)) { memcpy(&msg.arg3,&ohms,sizeof(uint32_t)); //raw IEEE float is transmitted transmit(&msg,TXCOUNT); printP(PSTR("transmit light\n")); } #endif } //anemometer if(anemo_present && r_anemo==0) { if(gusts>speedmax) {speedmax=gusts; dirmax=dir;} sumspeedx += speed * cosf(2*M_PI*dir/16); sumspeedy += speed * sinf(2*M_PI*dir/16); ++nanemo; #ifdef DEBUG { char c[32]; sprintf(c,"anemo samples %d\n",nanemo); print(c); } #endif if(nanemo==N_AVER_WIND) // transmit - N_AVER_WIND is large enough not to be too frequent { //compute and transmit average (256* integer sum and direction) sumspeedx *= 256./N_AVER_WIND; sumspeedy *= 256./N_AVER_WIND; float fspeed = sqrtf(sumspeedx*sumspeedx + sumspeedy*sumspeedy); float tmp= fspeed==0.?0.:atan2f(sumspeedy,sumspeedx); float fdir = (tmp<0.?2.*M_PI+tmp:tmp)/2./M_PI*16*256; msg.report_type=M2_WIND; msg.arg1=0; msg.arg2=(uint16_t) fdir; msg.arg3=(uint32_t) fspeed; transmit(&msg,TXCOUNT); printP(PSTR("transmit anemo\n")); while(txcount || outcodelen) {delay_ms(10); watchdog(1);} watchdog(1); delay_ms(1000); //separate the two transmits watchdog(1); delay_ms(1000); //separate the two transmits watchdog(1); delay_ms(1000); //separate the two transmits //transmit maximum msg.report_type=M2_WIND_GUSTS; msg.arg1=0; msg.arg2=(uint16_t) dirmax <<8; msg.arg3=(uint32_t) speedmax<<8; transmit(&msg,TXCOUNT); printP(PSTR("transmit anemo gusts\n")); //zero sums nanemo=0; dirmax=0; speedmax=0; sumspeedx= sumspeedy=0.; } } //update presence of rain gauge time to time if(!thermo_present && (pass&1023)==0) { smt_present = check_thermo_smt(); if(smt_present) thermo_present=1; else thermo_present= ! ds18b20_reset(0); } if(!thermo2_present && (pass&1023)==1) { smt2_present = check_thermo2_smt(); if(smt2_present) thermo2_present=1; else thermo2_present= ! ds18b20_reset(1); } //rain gauge if(thermo_present) {sprintf(c,"Train= %.2fC\n",0.01*temprain); print(c);} int16_t threshold=10; if(heater) threshold=25; //do not transmit so frequently about the r.g. temperature when heating it if( ((temprain-temprainold)>=threshold || (temprain-temprainold)<= -threshold) || (pass&0x7f)==0 || rainpass>1023 || nbuckets > 0) { cbi(SREG,7); nrain=nbuckets; nbuckets=0; sbi(SREG,7); char c[32]; sprintf(c,"Rain = %d\n",nrain); print(c); msg.report_type=M2_RAIN; msg.arg1= nrain; msg.arg2= temprain; transmit(&msg,TXCOUNT+(nrain>0?5:0)); //message about a bucket must not be lost printP(PSTR("transmit temp+rain\n")); temprainold=temprain; nrain=0; rainpass=0; } //control heater relay with some hysteresis and max duty cycle if(thermo_present) { if(heater==0 && temprain < (int16_t) eeprom_read_word(&hyst_on) ) {printP(PSTR("heater on\n")); sbi(PORTE,PE3); heater=1; heater_count=0; } if((heater==1 || bit_is_set(PORTE,PE3)) && temprain > (int16_t) eeprom_read_word(&hyst_off) ) {printP(PSTR("heater off\n")); cbi(PORTE,PE3); heater=0;} if(heater==1) //manage duty cycle { if((heater_count&31) < 24) sbi(PORTE,PE3); else cbi(PORTE,PE3); ++heater_count; } else cbi(PORTE,PE3); } //voltage sprintf(c,"U=%.2fV\n",0.01*volts); print(c); if(volts>voltsold+100 || voltsold>volts+100 || (pass&0x3ff)==0 ) { voltsold=volts; msg.report_type=M2_VOLTAGE; msg.arg2= volts; transmit(&msg,TXCOUNT); printP(PSTR("transmit voltage\n")); } //reset anemometer if it stops working #ifdef HAS_ANEMO_TX20 if(nbad>=50) { printP(PSTR("too many anemo errors, anemo_reset_tx20\n")); anemo_reset_tx20(); anemo_present=check_anemo(); msg.report_type=M2_WIND; msg.arg1=1; msg.arg2=anemo_present; transmit(&msg,TXCOUNT); printP(PSTR("transmit anemo\n")); } #endif //check if anemo has been connected in the meantime #ifdef HAS_ANEMO_TX20 if(!anemo_present && (pass & 255 )==0 ) anemo_present=check_anemo(); #else #ifdef HAS_ANEMO_WH1080 if(!anemo_present && (pass & 255 )==0 ) anemo_present=anemo_reset_wh1080(); watchdog(1); delay_ms(1000); watchdog(1); delay_ms(1000); #else //delay of the approx same time as check_anemo { watchdog(1); delay_ms(1000); watchdog(1); delay_ms(1000); } #endif #endif watchdog(1); //delay_ms(1000); no, would be too late to read next anemo message } }