/* JetiBox.cpp, Version 1.0 beta July 2010, by Uwe Gartmann Library acts as a Sensor when connected to a Jeti Receiver written for Arduino Mega / ArduPilot Mega This library is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2.1 of the License, or (at your option) any later version. This library 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 Lesser General Public License for more details. You should have received a copy of the GNU Lesser General Public License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ #include #include #include "wiring.h" #include "mySerial0.h" #include "JetiBox.h" #define LCDLine1 1 #define LCDLine2 17 #define LCDMaxChar 32 //define Jeti-Box Display struct jeti_box { unsigned char lcd[32]; volatile unsigned char lcdpos; volatile unsigned char keys; volatile unsigned char sendpos; }; // create jbox jeti_box jb = {{0},0,0,0}; unsigned char dummy; unsigned char lastkey = 0; ISR(USART3_RX_vect) //serial data available { // save response data to keys dummy = UDR3; if (dummy != 0xFF) { jb.keys = dummy; // disable this interrupt UCSR3B &= ~(1< interrupt is enabled (function start() ), send startbyte with 9.bit=0 * jbox.sendpos = 1-32 -> send display data with 9.bit=1 * jbox.sendpos = 33 -> send endbyte with 9.bit=0 * jbox.sendpos = 34 -> reset sendpos=0 -> disable this interrupt */ { switch (jb.sendpos) { case 0: // send start byte with 9.bit=0 UCSR3B &= ~(1< 0 jb.sendpos = 0; // enable receiver interrupt for reading key byte UCSR3B |= (1<>8); //high byte UBRR3L=_UBRR3; //low byte // Set frame format: 9data, odd parity, 2stop bit UCSR3C = (0<>4) xor 0x0F; if (lastkey==c) { return 0; }else{ return lastkey = c; } } void JetiBox::write(uint8_t c) { jb.lcd[jb.lcdpos] = c; if (jb.lcdpos < LCDMaxChar) { jb.lcdpos++; } } void JetiBox::line1() { jb.lcdpos = LCDLine1; } void JetiBox::line2() { jb.lcdpos = LCDLine2; } // Preinstantiate Objects ////////////////////////////////////////////////////// JetiBox JBox;