/*** Tester sketch for openLRS TX modules ***/ #include //####### TX BOARD TYPE ####### // 0 = Original M1 TX from Flytron // 2 = Original M2/M3 Tx Board or OrangeRx UHF TX // 3 = OpenLRS Rx v2 Board works as TX // 4 = OpenLRSngTX (tbd.) #define HW 4 #define FREQ 869300000 #if (HW==0) #define PPM_IN A5 #define RF_OUT_INDICATOR A4 #define BUZZER 9 #define BTN 10 #define PPM_Pin_Interrupt_Setup PCMSK1 = 0x20;PCICR|=(1<255) { ocr=255; } if (!ocr) { ocr=1; } OCR2A = ocr; TCCR2A |= (1<255) { ocr=255; } if (!ocr) { ocr=1; } OCR2A = ocr; TCCR2A |= (1< stopPulse) ? TIMER1_PERIOD : 0) + stopPulse - startPulse; if (pulseWidth > 5000) { // Verify if this is the sync pulse (2.5ms) ppmCounter = 0; // -> restart the channel counter } else if ((pulseWidth > 1400) && (ppmCounter < PPM_CHANNELS)) { // extra channels will get ignored here PPM[ppmCounter] = (pulseWidth / 2); // Store measured pulse length in us ppmCounter++; // Advance to next channel } else { ppmCounter = PPM_CHANNELS; // glitch ignore rest of data } startPulse = stopPulse; // Save time at pulse start } void setupPPMinput() { // Setup timer1 for input capture (PSC=8 -> 0.5ms precision, top at 20ms) TCCR1A = ((1 << WGM10) | (1 << WGM11)); TCCR1B = ((1 << WGM12) | (1 << WGM13) | (1 << CS11) | (1 << ICES1)); OCR1A = TIMER1_PERIOD; TIMSK1 |= (1 << ICIE1); // Enable timer1 input capture interrupt } #else // sample PPM using pinchange interrupt ISR(PPM_Signal_Interrupt) { uint16_t time_temp; if (PPM_Signal_Edge_Check) { // Only works with rising edge of the signal time_temp = TCNT1; // read the timer1 value TCNT1 = 0; // reset the timer1 value for next if (time_temp > 5000) { // new frame detection (>2.5ms) ppmCounter = 0; // -> restart the channel counter } else if ((time_temp > 1400) && (ppmCounter < PPM_CHANNELS)) { PPM[ppmCounter] = (time_temp / 2); // Store measured pulse length (converted) ppmCounter++; // Advance to next channel } else { ppmCounter = PPM_CHANNELS; // glitch ignore rest of data } } } void setupPPMinput(void) { // Setup timer1 for input capture (PSC=8 -> 0.5ms precision, top at 20ms) TCCR1A = ((1 << WGM10) | (1 << WGM11)); TCCR1B = ((1 << WGM12) | (1 << WGM13) | (1 << CS11)); OCR1A = TIMER1_PERIOD; TIMSK1 = 0; PPM_Pin_Interrupt_Setup } #endif // **** SPI bit banging functions #define NOP() __asm__ __volatile__("nop") #define RF22B_PWRSTATE_POWERDOWN 0x00 #define RF22B_PWRSTATE_READY 0x01 #define RF22B_PACKET_SENT_INTERRUPT 0x04 #define RF22B_PWRSTATE_RX 0x05 #define RF22B_PWRSTATE_TX 0x09 #define RF22B_Rx_packet_received_interrupt 0x02 uint8_t ItStatus1, ItStatus2; void spiWriteBit(uint8_t b) { if (b) { SCK_off; NOP(); SDI_on; NOP(); SCK_on; NOP(); } else { SCK_off; NOP(); SDI_off; NOP(); SCK_on; NOP(); } } uint8_t spiReadBit(void) { uint8_t r = 0; SCK_on; NOP(); if (SDO_1) { r = 1; } SCK_off; NOP(); return r; } void spiSendCommand(uint8_t command) { nSEL_on; SCK_off; nSEL_off; for (uint8_t n = 0; n < 8 ; n++) { spiWriteBit(command & 0x80); command = command << 1; } SCK_off; } void spiSendAddress(uint8_t i) { spiSendCommand(i & 0x7f); } void spiWriteData(uint8_t i) { for (uint8_t n = 0; n < 8; n++) { spiWriteBit(i & 0x80); i = i << 1; } SCK_off; } uint8_t spiReadData(void) { uint8_t Result = 0; SCK_off; for (uint8_t i = 0; i < 8; i++) { //read fifo data byte Result = (Result << 1) + spiReadBit(); } return(Result); } uint8_t spiReadRegister(uint8_t address) { uint8_t result; spiSendAddress(address); result = spiReadData(); nSEL_on; return(result); } void spiWriteRegister(uint8_t address, uint8_t data) { address |= 0x80; // spiSendCommand(address); spiWriteData(data); nSEL_on; } void setup() { Serial.begin(115200); buzzerInit(); pinMode(Red_LED,OUTPUT); pinMode(Green_LED,OUTPUT); #ifdef Red_LED2 pinMode(Red_LED2,OUTPUT); pinMode(Green_LED2,OUTPUT); #endif pinMode(BTN,INPUT); digitalWrite(BTN,HIGH); //enable pullup pinMode(PPM_IN,INPUT); digitalWrite(PPM_IN,HIGH); //enable pullup pinMode(SDO_pin, INPUT); pinMode(SDI_pin, OUTPUT); pinMode(SCLK_pin, OUTPUT); pinMode(nSel_pin, OUTPUT); pinMode(IRQ_pin, INPUT); #ifdef SDN_pin pinMode(SDN_pin, OUTPUT); digitalWrite(SDN_pin, LOW); #endif nSEL_on; setupPPMinput(); } void buzzerTest() { Serial.println("Buzzer test!"); buzzerOn(2000); delay(500); buzzerOn(1000); delay(500); buzzerOn(500); delay(500); buzzerOff(); Serial.println("DONE"); } void ledTest() { Serial.println("LED test!"); Red_LED_ON; delay(500); Green_LED_ON; delay(500); Red_LED_OFF; delay(500); Green_LED_OFF; Serial.println("DONE"); } void btnTest() { Serial.println("BUTTON test!"); boolean oldbtn = !digitalRead(BTN); while(!Serial.available()) { boolean newbtn = digitalRead(BTN); if (oldbtn!=newbtn) { Serial.println(newbtn?"BTN UP":"BTN DOWN"); oldbtn=newbtn; } } Serial.println("DONE"); } void ppmTest() { Serial.println("PPM input test!"); while(!Serial.available()) { for (int c=0; c> 8)); spiWriteRegister(0x77, (fc & 0xff)); } void TX_test(uint8_t power) { Serial.print("TX ON at powerlevel "); Serial.println(power&7); Green_LED_ON ItStatus1 = spiReadRegister(0x03); // read status, clear interrupt ItStatus2 = spiReadRegister(0x04); spiWriteRegister(0x06, 0x00); // no wakeup up, lbd, spiWriteRegister(0x07, RF22B_PWRSTATE_READY); // disable lbd, wakeup timer, use internal 32768,xton = 1; in ready mode spiWriteRegister(0x09, 0x7f); // (default) c = 12.5p spiWriteRegister(0x0a, 0x05); #if (HW==4) spiWriteRegister(0x0b, 0x15); // gpio0 TX State spiWriteRegister(0x0c, 0x12); // gpio1 RX State #else spiWriteRegister(0x0b, 0x12); // gpio0 TX State spiWriteRegister(0x0c, 0x15); // gpio1 RX State #endif spiWriteRegister(0x0d, 0xfd); // gpio 2 micro-controller clk output spiWriteRegister(0x0e, 0x00); // gpio 0, 1,2 NO OTHER FUNCTION. spiWriteRegister(0x70, 0x2C); // disable manchest spiWriteRegister(0x30, 0x00); //disable packet handling spiWriteRegister(0x79, 0); // start channel spiWriteRegister(0x7a, 0x05); // 50khz step size (10khz x value) // no hopping spiWriteRegister(0x71, 0x12); // trclk=[00] no clock, dtmod=[01] direct using SPI, fd8=0 eninv=0 modtyp=[10] FSK spiWriteRegister(0x72, 0x02); // fd (frequency deviation) 2*625Hz == 1.25kHz spiWriteRegister(0x73, 0x00); spiWriteRegister(0x74, 0x00); // no offset rfmSetCarrierFrequency(FREQ); spiWriteRegister(0x6d, power & 0x07); delay(10); spiWriteRegister(0x07, RF22B_PWRSTATE_TX); // to tx mode delay(10); beacon_tone(500, 5); spiWriteRegister(0x07, RF22B_PWRSTATE_READY); Green_LED_OFF Serial.println("DONE"); } void rx_reset(void) { spiWriteRegister(0x07, RF22B_PWRSTATE_READY); spiWriteRegister(0x7e, 36); // threshold for rx almost full, interrupt when 1 byte received spiWriteRegister(0x08, 0x03); //clear fifo disable multi packet spiWriteRegister(0x08, 0x00); // clear fifo, disable multi packet spiWriteRegister(0x07, RF22B_PWRSTATE_RX); // to rx mode spiWriteRegister(0x05, RF22B_Rx_packet_received_interrupt); ItStatus1 = spiReadRegister(0x03); //read the Interrupt Status1 register ItStatus2 = spiReadRegister(0x04); } void to_rx_mode(void) { ItStatus1 = spiReadRegister(0x03); ItStatus2 = spiReadRegister(0x04); spiWriteRegister(0x07, RF22B_PWRSTATE_READY); delay(10); rx_reset(); NOP(); } uint8_t rfmGetRSSI(void) { return spiReadRegister(0x26); } void rssiTest(void) { Serial.println("RSSI test"); while (Serial.available()) { Serial.read(); } to_rx_mode(); spiWriteRegister(0x1c, 0x12); // 41.7kHz rfmSetCarrierFrequency(FREQ); while (!Serial.available()) { Serial.println(rfmGetRSSI()); delay(100); } spiWriteRegister(0x07, RF22B_PWRSTATE_READY); //never exit!! } struct rfm22_modem_regs { uint32_t bps; uint8_t r_1c, r_1d, r_1e, r_20, r_21, r_22, r_23, r_24, r_25, r_2a, r_6e, r_6f, r_70, r_71, r_72; }; struct rfm22_modem_regs bind_params = { 9600, 0x05, 0x40, 0x0a, 0xa1, 0x20, 0x4e, 0xa5, 0x00, 0x20, 0x24, 0x4e, 0xa5, 0x2c, 0x23, 0x30 }; void setModemRegs(struct rfm22_modem_regs* r) { spiWriteRegister(0x1c, r->r_1c); spiWriteRegister(0x1d, r->r_1d); spiWriteRegister(0x1e, r->r_1e); spiWriteRegister(0x20, r->r_20); spiWriteRegister(0x21, r->r_21); spiWriteRegister(0x22, r->r_22); spiWriteRegister(0x23, r->r_23); spiWriteRegister(0x24, r->r_24); spiWriteRegister(0x25, r->r_25); spiWriteRegister(0x2a, r->r_2a); spiWriteRegister(0x6e, r->r_6e); spiWriteRegister(0x6f, r->r_6f); spiWriteRegister(0x70, r->r_70); spiWriteRegister(0x71, r->r_71); spiWriteRegister(0x72, r->r_72); } void init_rfm() { ItStatus1 = spiReadRegister(0x03); // read status, clear interrupt ItStatus2 = spiReadRegister(0x04); spiWriteRegister(0x06, 0x00); // disable interrupts spiWriteRegister(0x07, RF22B_PWRSTATE_READY); // disable lbd, wakeup timer, use internal 32768,xton = 1; in ready mode spiWriteRegister(0x09, 0x7f); // c = 12.5p spiWriteRegister(0x0a, 0x05); #if (HW==4) spiWriteRegister(0x0b, 0x15); // gpio0 RX State spiWriteRegister(0x0c, 0x12); // gpio1 TX State #else spiWriteRegister(0x0b, 0x12); // gpio0 TX State spiWriteRegister(0x0c, 0x15); // gpio1 RX State #endif spiWriteRegister(0x0d, 0xfd); // gpio 2 micro-controller clk output spiWriteRegister(0x0e, 0x00); // gpio 0, 1,2 NO OTHER FUNCTION. setModemRegs(&bind_params); // Packet settings spiWriteRegister(0x30, 0x8c); // enable packet handler, msb first, enable crc, spiWriteRegister(0x32, 0x0f); // no broadcast, check header bytes 3,2,1,0 spiWriteRegister(0x33, 0x42); // 4 byte header, 2 byte synch, variable pkt size spiWriteRegister(0x34, 0x0a); // 10 nibbles (40 bit preamble) spiWriteRegister(0x35, 0x2a); // preath = 5 (20bits), rssioff = 2 spiWriteRegister(0x36, 0x2d); // synchronize word 3 spiWriteRegister(0x37, 0xd4); // synchronize word 2 spiWriteRegister(0x38, 0x00); // synch word 1 (not used) spiWriteRegister(0x39, 0x00); // synch word 0 (not used) for (uint8_t i=0; i<4; i++) { spiWriteRegister(0x3a + i, i * 0x11); // tx header spiWriteRegister(0x3f + i, i * 0x11); // rx header } spiWriteRegister(0x43, 0xff); // all the bit to be checked spiWriteRegister(0x44, 0xff); // all the bit to be checked spiWriteRegister(0x45, 0xff); // all the bit to be checked spiWriteRegister(0x46, 0xff); // all the bit to be checked spiWriteRegister(0x6d, 7); spiWriteRegister(0x79, 0); spiWriteRegister(0x7a, 1); // channel spacing spiWriteRegister(0x73, 0x00); spiWriteRegister(0x74, 0x00); // no offset rfmSetCarrierFrequency(FREQ); } void tx_packet(uint8_t* pkt, uint8_t size) { spiWriteRegister(0x3e, size); // total tx size for (uint8_t i = 0; i < size; i++) { spiWriteRegister(0x7f, pkt[i]); } spiWriteRegister(0x05, RF22B_PACKET_SENT_INTERRUPT); ItStatus1 = spiReadRegister(0x03); //read the Interrupt Status1 register ItStatus2 = spiReadRegister(0x04); uint32_t tx_start = micros(); spiWriteRegister(0x07, RF22B_PWRSTATE_TX); // to tx mode while ((nIRQ_1) && ((micros() - tx_start)<100000)); if (nIRQ_1) { Serial.println("TX timeout!!!!"); Serial.print("Status regs are: 2=0x"); Serial.print(spiReadRegister(0x02),16); Serial.print(" 3=0x"); Serial.print(spiReadRegister(0x03),16); Serial.print(" 4=0x"); Serial.println(spiReadRegister(0x04),16); } spiWriteRegister(0x07, RF22B_PWRSTATE_READY); Serial.print("TX took:"); Serial.println(micros() - tx_start); } void help() { Serial.println("1 - buzzer test"); Serial.println("2 - LED test (red/both/green/off)"); Serial.println("3 - button test"); Serial.println("4 - PPM input test"); Serial.println("5 - RFMxx SPI test"); Serial.println("6 - RFMxx interrupt test"); Serial.println("7 - RFMxx RSSI read test"); Serial.println("8 - RFMxx packet transmit test (make sure you have antenna connected!)"); Serial.println("9 - RFMxx continous transmit (beacon) test (MAKE SURE YOU HAVE ANTENNA CONNECTED!)"); } void loop() { while (!Serial.available()); char ch=Serial.read(); delay(100); while (Serial.available()) Serial.read(); switch (ch) { case '1': buzzerTest(); break; case '2': ledTest(); break; case '3': btnTest(); break; case '4': ppmTest(); break; case '5': rfmcomTest(); break; case '6': rfmintTest(); break; case '7': rssiTest(); break; case '8': Green_LED_ON init_rfm(); tx_packet((uint8_t *)"AABBCCDDEEFF",12); Green_LED_OFF break; case '9': TX_test(7); break; default: help(); break; } }