Compare commits

..

3 Commits

Author SHA1 Message Date
morgan 8e5a101b1f fix formatting, comments 2016-07-03 13:27:01 -07:00
morgan bdd06ce525 updated readme 2016-07-03 13:23:03 -07:00
morgan a242fa3b31 update for I2C 2016-06-30 20:09:11 -07:00
69 changed files with 33627 additions and 5394 deletions

738
AFSK.cpp Normal file
View File

@ -0,0 +1,738 @@
#include <Arduino.h>
#include "HamShield.h"
#include "SimpleFIFO.h"
#include <util/atomic.h>
#define PHASE_BIT 8
#define PHASE_INC 1
#define PHASE_MAX (SAMPLEPERBIT * PHASE_BIT)
#define PHASE_THRES (PHASE_MAX / 2)
#define BIT_DIFFER(bitline1, bitline2) (((bitline1) ^ (bitline2)) & 0x01)
#define EDGE_FOUND(bitline) BIT_DIFFER((bitline), (bitline) >> 1)
#define PPOOL_SIZE 2
#define AFSK_SPACE 2200
#define AFSK_MARK 1200
// Timers
volatile unsigned long lastTx = 0;
volatile unsigned long lastTxEnd = 0;
volatile unsigned long lastRx = 0;
#define T_BIT ((unsigned int)(SAMPLERATE/BITRATE))
#ifdef PACKET_PREALLOCATE
SimpleFIFO<AFSK::Packet *,PPOOL_SIZE> preallocPool;
AFSK::Packet preallocPackets[PPOOL_SIZE];
#endif
void AFSK::Encoder::process() {
// We're on the start of a byte position, so fetch one
if(bitPosition == 0) {
if(preamble) { // Still in preamble
currentByte = HDLC_PREAMBLE;
--preamble; // Decrement by one
} else {
if(!packet) { // We aren't on a packet, grab one
// Unless we already sent enough
if(maxTx-- == 0) {
stop();
lastTxEnd = millis();
return;
}
packet = pBuf.getPacket();
if(!packet) { // There actually weren't any
stop(); // Stop transmitting and return
lastTxEnd = millis();
return;
}
lastTx = millis();
currentBytePos = 0;
nextByte = HDLC_FRAME; // Our next output should be a frame boundary
hdlc = true;
}
// We ran out of actual data, provide an HDLC frame (idle)
if(currentBytePos == packet->len && nextByte == 0) {
// We also get here if nextByte isn't set, to handle empty frames
pBuf.freePacket(packet);
packet = pBuf.getPacket(); // Get the next, if any
//packet = NULL;
currentBytePos = 0;
nextByte = 0;
currentByte = HDLC_FRAME;
hdlc = true;
} else {
if(nextByte) {
// We queued up something other than the actual stream to be sent next
currentByte = nextByte;
nextByte = 0;
} else {
// Get the next byte to send, but if it's an HDLC frame, escape it
// and queue the real byte for the next cycle.
currentByte = packet->getByte();
if(currentByte == HDLC_FRAME) {
nextByte = currentByte;
currentByte = HDLC_ESCAPE;
} else {
currentBytePos++;
}
hdlc = false; // If we get here, it will be NRZI bit stuffed
}
}
}
}
// Pickup the last bit
currentBit = currentByte & 0x1;
if(lastZero == 5) {
currentBit = 0; // Force a 0 bit output
} else {
currentByte >>= 1; // Bit shift it right, for the next round
++bitPosition; // Note our increase in position
}
// To handle NRZI 5 bit stuffing, count the bits
if(!currentBit || hdlc)
lastZero = 0;
else
++lastZero;
// NRZI and AFSK uses toggling 0s, "no change" on 1
// So, if not a 1, toggle to the opposite tone
if(!currentBit)
currentTone = !currentTone;
if(currentTone == 0) {
PORTD |= _BV(7);
dds->setFrequency(AFSK_SPACE);
} else {
PORTD &= ~_BV(7);
dds->setFrequency(AFSK_MARK);
}
}
bool AFSK::Encoder::start() {
if(!done || sending) {
return false;
}
if(randomWait > millis()) {
return false;
}
// First real byte is a frame
currentBit = 0;
lastZero = 0;
bitPosition = 0;
//bitClock = 0;
preamble = 0b110000; // 6.7ms each, 23 = 153ms
done = false;
hdlc = true;
packet = 0x0; // No initial packet, find in the ISR
currentBytePos = 0;
maxTx = 3;
sending = true;
nextByte = 0;
dds->setFrequency(0);
dds->on();
return true;
}
void AFSK::Encoder::stop() {
randomWait = 0;
sending = false;
done = true;
dds->setFrequency(0);
dds->off();
}
AFSK::Decoder::Decoder() {
// Initialize the sampler delay line (phase shift)
//for(unsigned char i = 0; i < SAMPLEPERBIT/2; i++)
// delay_fifo.enqueue(0);
}
bool AFSK::HDLCDecode::hdlcParse(bool bit, SimpleFIFO<uint8_t,HAMSHIELD_AFSK_RX_FIFO_LEN> *fifo) {
bool ret = true;
demod_bits <<= 1;
demod_bits |= bit ? 1 : 0;
// Flag
if(demod_bits == HDLC_FRAME) {
fifo->enqueue(HDLC_FRAME);
rxstart = true;
currchar = 0;
bit_idx = 0;
return ret;
}
// Reset
if((demod_bits & HDLC_RESET) == HDLC_RESET) {
rxstart = false;
lastRx = millis();
return ret;
}
if(!rxstart) {
return ret;
}
// Stuffed?
if((demod_bits & 0x3f) == 0x3e)
return ret;
if(demod_bits & 0x01)
currchar |= 0x80;
if(++bit_idx >= 8) {
if(currchar == HDLC_FRAME ||
currchar == HDLC_RESET ||
currchar == HDLC_ESCAPE) {
fifo->enqueue(HDLC_ESCAPE);
}
fifo->enqueue(currchar & 0xff);
currchar = 0;
bit_idx = 0;
} else {
currchar >>= 1;
}
return ret;
}
template <typename T, int size>
class FastRing {
private:
T ring[size];
uint8_t position;
public:
FastRing(): position(0) {}
inline void write(T value) {
ring[(position++) & (size-1)] = value;
}
inline T read() const {
return ring[position & (size-1)];
}
inline T readn(uint8_t n) const {
return ring[(position + (~n+1)) & (size-1)];
}
};
// Create a delay line that's half the length of the bit cycle (-90 degrees)
FastRing<uint8_t,(T_BIT/2)> delayLine;
// Handle the A/D converter interrupt (hopefully quickly :)
void AFSK::Decoder::process(int8_t curr_sample) {
// Run the same through the phase multiplier and butterworth filter
iir_x[0] = iir_x[1];
iir_x[1] = ((int8_t)delayLine.read() * curr_sample) >> 2;
iir_y[0] = iir_y[1];
iir_y[1] = iir_x[0] + iir_x[1] + (iir_y[0] >> 1) + (iir_y[0]>>3) + (iir_y[0]>>5);
// Place this ADC sample into the delay line
delayLine.write(curr_sample);
// Shift the bit into place based on the output of the discriminator
sampled_bits <<= 1;
sampled_bits |= (iir_y[1] > 0) ? 1 : 0;
// If we found a 0/1 transition, adjust phases to track
if(EDGE_FOUND(sampled_bits)) {
if(curr_phase < PHASE_THRES)
curr_phase += PHASE_INC;
else
curr_phase -= PHASE_INC;
}
// Move ahead in phase
curr_phase += PHASE_BIT;
// If we've gone over the phase maximum, we should now have some data
if(curr_phase >= PHASE_MAX) {
curr_phase %= PHASE_MAX;
found_bits <<= 1;
// If we have 3 bits or more set, it's a positive bit
register uint8_t bits = sampled_bits & 0x07;
if(bits == 0x07 || bits == 0x06 || bits == 0x05 || bits == 0x03) {
found_bits |= 1;
}
hdlc.hdlcParse(!EDGE_FOUND(found_bits), &rx_fifo); // Process it
}
}
// This routine uses a pre-allocated Packet structure
// to save on the memory requirements of the stream data
bool AFSK::Decoder::read() {
bool retVal = false;
if(!currentPacket) { // We failed a prior memory allocation
currentPacket = pBuf.makePacket(PACKET_MAX_LEN);
if(!currentPacket) // Still nothing
return false;
}
// While we have AFSK receive FIFO bytes...
while(rx_fifo.count()) {
// Grab the character
char c = rx_fifo.dequeue();
bool escaped = false;
if(c == HDLC_ESCAPE) { // We received an escaped byte, mark it
escaped = true;
// Do we want to keep HDLC_ESCAPEs in the packet?
//currentPacket->append(HDLC_ESCAPE); // Append without FCS
c = rx_fifo.dequeue(); // Reset to the next character
}
// Append all the bytes
// This will include unescaped HDLC_FRAME bytes
if(c != HDLC_FRAME || escaped) // Append frame if it is escaped
currentPacket->appendFCS(c); // Escaped characters and all else go into FCS
if(currentPacket->len > PACKET_MAX_LEN) {
// We've now gone too far and picked up far too many bytes
// Cancel this frame, start back at the beginning
currentPacket->clear();
continue;
}
// We have a frame boundary, if it isn't escaped
// If it's escaped, it was part of the data stream
if(c == HDLC_FRAME && !escaped) {
if(!currentPacket->len) {
currentPacket->clear(); // There wasn't any data, restart stream
continue;
} else {
// We have some bytes in stream, check it meets minimum payload length
// Min payload is 1 (flag) + 14 (addressing) + 2 (control/PID) + 1 (flag)
if(currentPacket->len >= 16) {
// We should end up here with a valid FCS due to the appendFCS
if(currentPacket->crcOK()) { // Magic number for the CRC check passing
// Valid frame, so, let's filter for control + PID
// Maximum search distance is 71 bytes to end of the address fields
// Skip the HDLC frame start
bool filtered = false;
for(unsigned char i = 0; i < (currentPacket->len<70?currentPacket->len:71); ++i) {
if((currentPacket->getByte() & 0x1) == 0x1) { // Found a byte with LSB set
// which marks the final address payload
// next two bytes should be the control/PID
//if(currentPacket->getByte() == 0x03 && currentPacket->getByte() == 0xf0) {
filtered = true;
break; // Found it
//}
}
}
if(!filtered) {
// Frame wasn't one we care about, discard
currentPacket->clear();
continue;
}
// It's all done and formatted, ready to go
currentPacket->ready = 1;
if(!pBuf.putPacket(currentPacket)) // Put it in the receive FIFO
pBuf.freePacket(currentPacket); // Out of FIFO space, so toss it
// Allocate a new one of maximum length
currentPacket = pBuf.makePacket(PACKET_MAX_LEN);
retVal = true;
}
}
}
// Restart the stream
currentPacket->clear();
}
}
return retVal; // This is true if we parsed a packet in this flow
}
void AFSK::Decoder::start() {
// Do this in start to allocate our first packet
currentPacket = pBuf.makePacket(PACKET_MAX_LEN);
/* ASSR &= ~(_BV(EXCLK) | _BV(AS2));
// Do non-inverting PWM on pin OC2B (arduino pin 3) (p.159).
// OC2A (arduino pin 11) stays in normal port operation:
// COM2B1=1, COM2B0=0, COM2A1=0, COM2A0=0
// Mode 1 - Phase correct PWM
TCCR2A = (TCCR2A | _BV(COM2B1)) & ~(_BV(COM2B0) | _BV(COM2A1) | _BV(COM2A0)) |
_BV(WGM21) | _BV(WGM20);
// No prescaler (p.162)
TCCR2B = (TCCR2B & ~(_BV(CS22) | _BV(CS21))) | _BV(CS20) | _BV(WGM22);
OCR2A = pow(2,COMPARE_BITS)-1;
OCR2B = 0;
// Configure the ADC and Timer1 to trigger automatic interrupts
TCCR1A = 0;
TCCR1B = _BV(CS11) | _BV(WGM13) | _BV(WGM12);
ICR1 = ((F_CPU / 8) / REFCLK) - 1;
ADMUX = _BV(REFS0) | _BV(ADLAR) | 0; // Channel 0, shift result left (ADCH used)
DDRC &= ~_BV(0);
PORTC &= ~_BV(0);
DIDR0 |= _BV(0);
ADCSRB = _BV(ADTS2) | _BV(ADTS1) | _BV(ADTS0);
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADATE) | _BV(ADIE) | _BV(ADPS2); // | _BV(ADPS0); */
}
AFSK::PacketBuffer::PacketBuffer() {
nextPacketIn = 0;
nextPacketOut = 0;
inBuffer = 0;
for(unsigned char i = 0; i < PACKET_BUFFER_SIZE; ++i) {
packets[i] = 0x0;
}
#ifdef PACKET_PREALLOCATE
for(unsigned char i = 0; i < PPOOL_SIZE; ++i) {
// Put some empty packets in the FIFO
preallocPool.enqueue(&preallocPackets[i]);
}
#endif
}
unsigned char AFSK::PacketBuffer::readyCount() volatile {
unsigned char i;
unsigned int cnt = 0;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
for(i = 0; i < PACKET_BUFFER_SIZE; ++i) {
if(packets[i] && packets[i]->ready)
++cnt;
}
}
return cnt;
}
// Return NULL on empty packet buffers
AFSK::Packet *AFSK::PacketBuffer::getPacket() volatile {
unsigned char i = 0;
AFSK::Packet *p = NULL;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
if(inBuffer == 0) {
return 0x0;
}
do {
p = packets[nextPacketOut];
if(p) {
packets[nextPacketOut] = 0x0;
--inBuffer;
}
nextPacketOut = ++nextPacketOut % PACKET_BUFFER_SIZE;
++i;
} while(!p && i<PACKET_BUFFER_SIZE);
// Return whatever we found, if anything
}
return p;
}
//void Packet::init(uint8_t *buf, unsigned int dlen, bool freeData) {
void AFSK::Packet::init(unsigned short dlen) {
//data = (unsigned char *)buf;
ready = 0;
#ifdef PACKET_PREALLOCATE
freeData = 0;
maxLen = PACKET_MAX_LEN; // Put it here instead
#else
freeData = 1;
dataPtr = (uint8_t *)malloc(dlen+16);
maxLen = dlen; // Put it here instead
#endif
type = PACKET_STATIC;
len = 0; // We had a length, but don't put it here.
dataPos = dataPtr;
readPos = dataPtr;
fcs = 0xffff;
}
// Allocate a new packet with a data buffer as set
AFSK::Packet *AFSK::PacketBuffer::makePacket(unsigned short dlen) {
AFSK::Packet *p;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
//Packet *p = findPooledPacket();
#ifdef PACKET_PREALLOCATE
if(preallocPool.count())
p = preallocPool.dequeue();
else p = NULL;
#else
p = new Packet(); //(Packet *)malloc(sizeof(Packet));
#endif
if(p) // If allocated
p->init(dlen);
}
return p; // Passes through a null on failure.
}
// Free a packet struct, mainly convenience
void AFSK::PacketBuffer::freePacket(Packet *p) {
if(!p)
return;
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
#ifdef PACKET_PREALLOCATE
preallocPool.enqueue(p);
#else
p->free();
/*unsigned char i;
for(i = 0; i < PPOOL_SIZE; ++i)
if(p == &(pPool[i]))
break;
if(i < PPOOL_SIZE)
pStatus &= ~(1<<i);*/
delete p;
#endif
}
}
// Put a packet onto the buffer array
bool AFSK::PacketBuffer::putPacket(Packet *p) volatile {
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
if(inBuffer >= PACKET_BUFFER_SIZE) {
return false;
}
packets[nextPacketIn] = p;
nextPacketIn = ++nextPacketIn % PACKET_BUFFER_SIZE;
++inBuffer;
}
return true;
}
// Print a single byte to the data array
size_t AFSK::Packet::write(uint8_t c) {
return (appendFCS(c)?1:0);
}
size_t AFSK::Packet::write(const uint8_t *ptr, size_t len) {
size_t i;
for(i = 0; i < len; ++i)
if(!appendFCS(ptr[i]))
break;
return i;
}
// Add a callsign, flagged as source, destination, or digi
// Also tell the routine the SSID to use and if this is the final callsign
size_t AFSK::Packet::appendCallsign(const char *callsign, uint8_t ssid, bool final) {
uint8_t i;
for(i = 0; i < strlen(callsign) && i < 6; i++) {
appendFCS(callsign[i]<<1);
}
if(i < 6) {
for(;i<6;i++) {
appendFCS(' '<<1);
}
}
uint8_t ssidField = (ssid&0xf) << 1;
// TODO: Handle digis in the address C bit
if(final) {
ssidField |= 0b01100001;
} else {
ssidField |= 0b11100000;
}
appendFCS(ssidField);
}
#ifdef PACKET_PARSER
// Process the AX25 frame and turn it into a bunch of useful strings
bool AFSK::Packet::parsePacket() {
uint8_t *d = dataPtr;
int i;
// First 7 bytes are destination-ssid
for(i = 0; i < 6; i++) {
dstCallsign[i] = (*d++)>>1;
if(dstCallsign[i] == ' ') {
dstCallsign[i] = '\0';
}
}
dstCallsign[6] = '\0';
dstSSID = ((*d++)>>1) & 0xF;
// Next 7 bytes are source-ssid
for(i = 0; i < 6; i++) {
srcCallsign[i] = (*d++)>>1;
if(srcCallsign[i] == ' ') {
srcCallsign[i] = '\0';
}
}
srcCallsign[6] = '\0';
srcSSID = *d++; // Don't shift yet, we need the LSB
digipeater[0][0] = '\0'; // Set null in case we have none anyway
if((srcSSID & 1) == 0) { // Not the last address field
int digi; // Which digi we're on
for(digi = 0; digi < 8; digi++) {
for(i = 0; i < 6; i++) {
digipeater[digi][i] = (*d++)>>1;
if(digipeater[digi][i] == ' ') {
digipeater[digi][i] = '\0';
}
}
uint8_t last = (*d) & 1;
digipeaterSSID[digi] = ((*d++)>>1) & 0xF;
if(last == 1)
break;
}
digipeater[digi][6] = '\0';
for(digi += 1; digi<8; digi++) { // Empty out the rest of them
digipeater[digi][0] = '\0';
}
}
// Now handle the SSID itself
srcSSID >>= 1;
srcSSID &= 0xF;
// After the address parsing, we end up on the control field
control = *d++;
// We have a PID if control type is U or I
// Control & 1 == 0 == I frame
// Control & 3 == 3 == U frame
if((control & 1) == 0 || (control & 3) == 3)
pid = *d++;
else pid = 0;
// If there is no PID, we have no data
if(!pid) {
iFrameData = NULL;
return true;
}
// At this point, we've walked far enough along that data is just at d
iFrameData = d;
// Cheat a little by setting the first byte of the FCS to 0, making it a string
// First FCS byte is found at -2, HDLC flags aren't in this buffer
dataPtr[len-2] = '\0';
return true;
}
#endif
void AFSK::Packet::printPacket(Stream *s) {
uint8_t i;
#ifdef PACKET_PARSER
if(!parsePacket()) {
s->print(F("Packet not valid"));
return;
}
s->print(srcCallsign);
if(srcSSID > 0) {
s->write('-');
s->print(srcSSID);
}
s->print(F(" > "));
s->print(dstCallsign);
if(dstSSID > 0) {
s->write('-');
s->print(dstSSID);
}
s->write(' ');
if(digipeater[0][0] != '\0') {
s->print(F("via "));
for(i = 0; i < 8; i++) {
if(digipeater[i][0] == '\0')
break;
s->print(digipeater[i]);
if(digipeaterSSID[i] != 0) {
s->write('-');
s->print(digipeaterSSID[i]);
}
if((digipeaterSSID[i] & _BV(7)) == _BV(7)) {
s->write('*'); // Digipeated already
}
// If we might have more, check to add a comma
if(i < 7 && digipeater[i+1][0] != '\0') {
s->write(',');
}
s->write(' ');
}
}
// This is an S frame, we can only print control info
if(control & 3 == 1) {
switch((control>>2)&3) {
case 0:
s->print(F("RR"));
break;
case 1:
s->print(F("RNR"));
break;
case 2:
s->print(F("REJ"));
break;
case 3: // Undefined
s->print(F("unk"));
break;
}
// Use a + to indicate poll bit
if(control & _BV(4) == _BV(4)) {
s->write('+');
}
} else if((control & 3) == 3) { // U Frame
s->print(F("U("));
s->print(control, HEX);
s->write(',');
s->print(pid, HEX);
s->print(F(") "));
} else if((control & 1) == 0) { // I Frame
s->print(F("I("));
s->print(control, HEX);
s->write(',');
s->print(pid, HEX);
s->print(F(") "));
}
s->print(F("len "));
s->print(len);
s->print(F(": "));
s->print((char *)iFrameData);
s->println();
#else // no packet parser, do a rudimentary print
// Second 6 bytes are source callsign
for(i=7; i<13; i++) {
s->write(*(dataPtr+i)>>1);
}
// SSID
s->write('-');
s->print((*(dataPtr+13) >> 1) & 0xF);
s->print(F(" -> "));
// First 6 bytes are destination callsign
for(i=0; i<6; i++) {
s->write(*(dataPtr+i)>>1);
}
// SSID
s->write('-');
s->print((*(dataPtr+6) >> 1) & 0xF);
// Control/PID next two bytes
// Skip those, print payload
for(i = 15; i<len; i++) {
s->write(*(dataPtr+i));
}
#endif
}
// Determine what we want to do on this ADC tick.
void AFSK::timer() {
static uint8_t tcnt = 0;
if(++tcnt == T_BIT && encoder.isSending()) {
PORTD |= _BV(6);
// Only run the encoder every 8th tick
// This is actually DDS RefClk / 1200 = 8, set as T_BIT
// A different refclk needs a different value
encoder.process();
tcnt = 0;
PORTD &= ~_BV(6);
} else {
decoder.process(((int8_t)(ADCH - 128)));
}
}
void AFSK::start(DDS *dds) {
afskEnabled = true;
encoder.setDDS(dds);
decoder.start();
}

301
AFSK.h Normal file
View File

@ -0,0 +1,301 @@
#ifndef _AFSK_H_
#define _AFSK_H_
#include <Arduino.h>
#include <SimpleFIFO.h>
#include <DDS.h>
#define SAMPLERATE 9600
#define BITRATE 1200
#define SAMPLEPERBIT (SAMPLERATE / BITRATE)
#define RX_FIFO_LEN 16
#define PACKET_BUFFER_SIZE 2
#define PACKET_STATIC 0
// Enable the packet parser which will tokenize the AX25 frame into easy strings
#define PACKET_PARSER
// If this is set, all the packet buffers will be pre-allocated at compile time
// This will use more RAM, but can make it easier to do memory planning.
// TODO: Make this actually work right and not crash.
#define PACKET_PREALLOCATE
// This is with all the digis, two addresses, and full payload
// Dst(7) + Src(7) + Digis(56) + Ctl(1) + PID(1) + Data(0-256) + FCS(2)
#define PACKET_MAX_LEN 330
// Minimum is Dst + Src + Ctl + FCS
#define AX25_PACKET_HEADER_MINLEN 17
// HDLC framing bits
#define HDLC_FRAME 0x7E
#define HDLC_RESET 0x7F
#define HDLC_PREAMBLE 0x00
#define HDLC_ESCAPE 0x1B
#define HDLC_TAIL 0x1C
class AFSK {
private:
volatile bool afskEnabled;
public:
bool enabled() { return afskEnabled; };
class Packet:public Print {
public:
Packet():Print() {};
virtual size_t write(uint8_t);
// Stock virtual method does what we want here.
//virtual size_t write(const char *);
virtual size_t write(const uint8_t *, size_t);
using Print::write;
unsigned char ready : 1;
unsigned char type : 2;
unsigned char freeData : 1;
unsigned short len;
unsigned short maxLen;
//void init(uint8_t *buf, unsigned int dlen, bool freeData);
void init(unsigned short dlen);
inline void free() {
if(freeData)
::free(dataPtr);
}
inline const unsigned char getByte(void) {
return *readPos++;
}
inline const unsigned char getByte(uint16_t p) {
return *(dataPtr+p);
}
inline void start() {
fcs = 0xffff;
// No longer put an explicit frame start here
//*dataPos++ = HDLC_ESCAPE;
//*dataPos++ = HDLC_FRAME;
//len = 2;
len = 0;
}
inline bool append(char c) {
if(len < maxLen) {
++len;
*dataPos++ = c;
return true;
}
return false;
}
#define UPDATE_FCS(d) e=fcs^(d); f=e^(e<<4); fcs=(fcs>>8)^(f<<8)^(f<<3)^(f>>4)
//#define UPDATE_FCS(d) s=(d)^(fcs>>8); t=s^(s>>4); fcs=(fcs<<8)^t^(t<<5)^(t<<12)
inline bool appendFCS(unsigned char c) {
register unsigned char e, f;
if(len < maxLen - 4) { // Leave room for FCS/HDLC
append(c);
UPDATE_FCS(c);
return true;
}
return false;
}
size_t appendCallsign(const char *callsign, uint8_t ssid, bool final = false);
inline void finish() {
append(~(fcs & 0xff));
append(~((fcs>>8) & 0xff));
// No longer append the frame boundaries themselves
//append(HDLC_ESCAPE);
//append(HDLC_FRAME);
ready = 1;
}
inline void clear() {
fcs = 0xffff;
len = 0;
readPos = dataPtr;
dataPos = dataPtr;
}
inline bool crcOK() {
return (fcs == 0xF0B8);
}
#ifdef PACKET_PARSER
bool parsePacket();
#endif
void printPacket(Stream *s);
private:
#ifdef PACKET_PREALLOCATE
uint8_t dataPtr[PACKET_MAX_LEN]; // 256 byte I frame + headers max of 78
#else
uint8_t *dataPtr;
#endif
#ifdef PACKET_PARSER
char srcCallsign[7];
uint8_t srcSSID;
char dstCallsign[7];
uint8_t dstSSID;
char digipeater[8][7];
uint8_t digipeaterSSID[8];
uint8_t *iFrameData;
uint8_t length;
uint8_t control;
uint8_t pid;
#endif
uint8_t *dataPos, *readPos;
unsigned short fcs;
};
class PacketBuffer {
public:
// Initialize the buffers
PacketBuffer();
// How many packets are in the buffer?
unsigned char count() volatile { return inBuffer; };
// And how many of those are ready?
unsigned char readyCount() volatile;
// Retrieve the next packet
Packet *getPacket() volatile;
// Create a packet structure as needed
// This does not place it in the queue
static Packet *makePacket(unsigned short);
// Conveniently free packet memory
static void freePacket(Packet *);
// Place a packet into the buffer
bool putPacket(Packet *) volatile;
private:
volatile unsigned char inBuffer;
Packet * volatile packets[PACKET_BUFFER_SIZE];
volatile unsigned char nextPacketIn;
volatile unsigned char nextPacketOut;
};
class Encoder {
public:
Encoder() {
randomWait = 1000; // At the very begin, wait at least one second
sending = false;
done = true;
packet = 0x0;
currentBytePos = 0;
nextByte = 0;
}
void setDDS(DDS *d) { dds = d; }
volatile inline bool isSending() volatile {
return sending;
}
volatile inline bool isDone() volatile {
return done;
}
volatile inline bool hasPackets() volatile {
return (pBuf.count() > 0);
}
inline bool putPacket(Packet *packet) {
return pBuf.putPacket(packet);
}
inline void setRandomWait() {
randomWait = 250 + (rand() % 1000) + millis();
}
bool start();
void stop();
void process();
private:
volatile bool sending;
byte currentByte;
byte currentBit : 1;
byte currentTone : 1;
byte lastZero : 3;
byte bitPosition : 3;
byte preamble : 6;
//byte bitClock;
bool hdlc;
byte nextByte;
byte maxTx;
Packet *packet;
PacketBuffer pBuf;
unsigned int currentBytePos;
volatile unsigned long randomWait;
volatile bool done;
DDS *dds;
};
class HDLCDecode {
public:
bool hdlcParse(bool, SimpleFIFO<uint8_t,RX_FIFO_LEN> *fifo);
volatile bool rxstart;
private:
uint8_t demod_bits;
uint8_t bit_idx;
uint8_t currchar;
};
class Decoder {
public:
Decoder();
void start();
bool read();
void process(int8_t);
inline bool dataAvailable() {
return (rx_fifo.count() > 0);
}
inline uint8_t getByte() {
return rx_fifo.dequeue();
}
inline uint8_t packetCount() volatile {
return pBuf.count();
}
inline Packet *getPacket() {
return pBuf.getPacket();
}
inline bool isReceiving() volatile {
return hdlc.rxstart;
}
private:
Packet *currentPacket;
//SimpleFIFO<int8_t,SAMPLEPERBIT/2+1> delay_fifo;
SimpleFIFO<uint8_t,RX_FIFO_LEN> rx_fifo; // This should be drained fairly often
int16_t iir_x[2];
int16_t iir_y[2];
uint8_t sampled_bits;
int8_t curr_phase;
uint8_t found_bits;
PacketBuffer pBuf;
HDLCDecode hdlc;
};
public:
inline bool read() {
return decoder.read();
}
volatile inline bool txReady() volatile {
if(encoder.isDone() && encoder.hasPackets())
return true;
return false;
}
volatile inline bool isDone() volatile { return encoder.isDone(); }
inline bool txStart() {
if(decoder.isReceiving()) {
encoder.setRandomWait();
return false;
}
return encoder.start();
}
inline bool putTXPacket(Packet *packet) {
bool ret = encoder.putPacket(packet);
if(!ret) // No room?
PacketBuffer::freePacket(packet);
return ret;
}
inline Packet *getRXPacket() {
return decoder.getPacket();
}
inline uint8_t rxPacketCount() volatile {
return decoder.packetCount();
}
//unsigned long lastTx;
//unsigned long lastRx;
void start(DDS *);
void timer();
Encoder encoder;
Decoder decoder;
};
#endif /* _AFSK_H_ */

175
DDS.cpp Normal file
View File

@ -0,0 +1,175 @@
#include <Arduino.h>
#include "DDS.h"
// To start the DDS, we use Timer1, set to the reference clock
// We use Timer2 for the PWM output, running as fast as feasible
void DDS::start() {
// Use the clkIO clock rate
ASSR &= ~(_BV(EXCLK) | _BV(AS2));
// First, the timer for the PWM output
// Setup the timer to use OC2B (pin 3) in fast PWM mode with a configurable top
// Run it without the prescaler
#ifdef DDS_PWM_PIN_3
TCCR2A = (TCCR2A | _BV(COM2B1)) & ~(_BV(COM2B0) | _BV(COM2A1) | _BV(COM2A0)) |
_BV(WGM21) | _BV(WGM20);
TCCR2B = (TCCR2B & ~(_BV(CS22) | _BV(CS21))) | _BV(CS20) | _BV(WGM22);
#else
// Alternatively, use pin 11
// Enable output compare on OC2A, toggle mode
TCCR2A = _BV(COM2A1) | _BV(WGM21) | _BV(WGM20);
//TCCR2A = (TCCR2A | _BV(COM2A1)) & ~(_BV(COM2A0) | _BV(COM2B1) | _BV(COM2B0)) |
// _BV(WGM21) | _BV(WGM20);
TCCR2B = _BV(CS20);
#endif
// Set the top limit, which will be our duty cycle accuracy.
// Setting Comparator Bits smaller will allow for higher frequency PWM,
// with the loss of resolution.
#ifdef DDS_PWM_PIN_3
OCR2A = pow(2,COMPARATOR_BITS)-1;
OCR2B = 0;
#else
OCR2A = 0;
#endif
#ifdef DDS_USE_ONLY_TIMER2
TIMSK2 |= _BV(TOIE2);
#endif
// Second, setup Timer1 to trigger the ADC interrupt
// This lets us use decoding functions that run at the same reference
// clock as the DDS.
// We use ICR1 as TOP and prescale by 8
TCCR1B = _BV(CS10) | _BV(WGM13) | _BV(WGM12);
TCCR1A = 0;
ICR1 = ((F_CPU / 1) / refclk) - 1;
#ifdef DDS_DEBUG_SERIAL
Serial.print(F("DDS SysClk: "));
Serial.println(F_CPU/8);
Serial.print(F("DDS RefClk: "));
Serial.println(refclk, DEC);
Serial.print(F("DDS ICR1: "));
Serial.println(ICR1, DEC);
#endif
// Configure the ADC here to automatically run and be triggered off Timer1
ADMUX = _BV(REFS0) | _BV(ADLAR) | 0; // Channel 0, shift result left (ADCH used)
DDRC &= ~_BV(0);
PORTC &= ~_BV(0);
DIDR0 |= _BV(0);
ADCSRB = _BV(ADTS2) | _BV(ADTS1) | _BV(ADTS0);
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADATE) | _BV(ADIE) | _BV(ADPS2); // | _BV(ADPS0);
}
void DDS::stop() {
// TODO: Stop the timers.
#ifndef DDS_USE_ONLY_TIMER2
TCCR1B = 0;
#endif
TCCR2B = 0;
}
// Set our current sine wave frequency in Hz
ddsAccumulator_t DDS::calcFrequency(unsigned short freq) {
// Fo = (M*Fc)/2^N
// M = (Fo/Fc)*2^N
ddsAccumulator_t newStep;
if(refclk == DDS_REFCLK_DEFAULT) {
// Try to use precalculated values if possible
if(freq == 2200) {
newStep = (2200.0 / (DDS_REFCLK_DEFAULT+DDS_REFCLK_OFFSET)) * pow(2,ACCUMULATOR_BITS);
} else if (freq == 1200) {
newStep = (1200.0 / (DDS_REFCLK_DEFAULT+DDS_REFCLK_OFFSET)) * pow(2,ACCUMULATOR_BITS);
} else if(freq == 2400) {
newStep = (2400.0 / (DDS_REFCLK_DEFAULT+DDS_REFCLK_OFFSET)) * pow(2,ACCUMULATOR_BITS);
} else if (freq == 1500) {
newStep = (1500.0 / (DDS_REFCLK_DEFAULT+DDS_REFCLK_OFFSET)) * pow(2,ACCUMULATOR_BITS);
} else if (freq == 600) {
newStep = (600.0 / (DDS_REFCLK_DEFAULT+DDS_REFCLK_OFFSET)) * pow(2,ACCUMULATOR_BITS);
}
} else {
newStep = pow(2,ACCUMULATOR_BITS)*freq / (refclk+refclkOffset);
}
return newStep;
}
// Degrees should be between -360 and +360 (others don't make much sense)
void DDS::setPhaseDeg(int16_t degrees) {
accumulator = degrees * (pow(2,ACCUMULATOR_BITS)/360.0);
}
void DDS::changePhaseDeg(int16_t degrees) {
accumulator += degrees * (pow(2,ACCUMULATOR_BITS)/360.0);
}
// TODO: Clean this up a bit..
void DDS::clockTick() {
/* if(running) {
accumulator += stepRate;
OCR2A = getDutyCycle();
}
return;*/
if(running) {
accumulator += stepRate;
if(timeLimited && tickDuration == 0) {
#ifndef DDS_PWM_PIN_3
OCR2A = 0;
#else
#ifdef DDS_IDLE_HIGH
// Set the duty cycle to 50%
OCR2B = pow(2,COMPARATOR_BITS)/2;
#else
// Set duty cycle to 0, effectively off
OCR2B = 0;
#endif
#endif
running = false;
accumulator = 0;
} else {
#ifdef DDS_PWM_PIN_3
OCR2B = getDutyCycle();
#else
OCR2A = getDutyCycle();
#endif
}
// Reduce our playback duration by one tick
tickDuration--;
} else {
// Hold it low
#ifndef DDS_PWM_PIN_3
OCR2A = 0;
#else
#ifdef DDS_IDLE_HIGH
// Set the duty cycle to 50%
OCR2B = pow(2,COMPARATOR_BITS)/2;
#else
// Set duty cycle to 0, effectively off
OCR2B = 0;
#endif
#endif
}
}
uint8_t DDS::getDutyCycle() {
#if ACCUMULATOR_BIT_SHIFT >= 24
uint16_t phAng;
#else
uint8_t phAng;
#endif
if(amplitude == 0) // Shortcut out on no amplitude
return 128>>(8-COMPARATOR_BITS);
phAng = (accumulator >> ACCUMULATOR_BIT_SHIFT);
int8_t position = pgm_read_byte_near(ddsSineTable + phAng); //>>(8-COMPARATOR_BITS);
// Apply scaling and return
int16_t scaled = position;
// output = ((duty * amplitude) / 256) + 128
// This keeps amplitudes centered around 50% duty
if(amplitude != 255) { // Amplitude is reduced, so do the full math
scaled *= amplitude;
scaled >>= 8+(8-COMPARATOR_BITS);
} else { // Otherwise, only shift for the comparator bits
scaled >>= (8-COMPARATOR_BITS);
}
scaled += 128>>(8-COMPARATOR_BITS);
return scaled;
}

228
DDS.h Normal file
View File

@ -0,0 +1,228 @@
#ifndef _DDS_H_
#define _DDS_H_
#include <avr/pgmspace.h>
// Use pin 3 for PWM? If not defined, use pin 11
// Quality on pin 3 is higher than on 11, as it can be clocked faster
// when the COMPARATOR_BITS value is less than 8
#define DDS_PWM_PIN_3
// Normally, we turn on timer2 and timer1, and have ADC sampling as our clock
// Define this to only use Timer2, and not start the ADC clock
// #define DDS_USE_ONLY_TIMER2
// Use a short (16 bit) accumulator. Phase accuracy is reduced, but speed
// is increased, along with a reduction in memory use.
#define SHORT_ACCUMULATOR
#ifdef SHORT_ACCUMULATOR
#define ACCUMULATOR_BITS 16
typedef uint16_t ddsAccumulator_t;
#else
#define ACCUMULATOR_BITS 32
typedef uint32_t ddsAccumulator_t;
#endif
// If defined, the timer will idle at 50% duty cycle
// This leaves it floating in the centre of the PWM/DAC voltage range
#define DDS_IDLE_HIGH
// Select how fast the PWM is, at the expense of level accuracy.
// A faster PWM rate will make for easier filtering of the output wave,
// while a slower one will allow for more accurate voltage level outputs,
// but will increase the filtering requirements on the output.
// 8 = 62.5kHz PWM
// 7 = 125kHz PWM
// 6 = 250kHz PWM
#ifdef DDS_PWM_PIN_3
#define COMPARATOR_BITS 6
#else // When using pin 11, we always want 8 bits
#define COMPARATOR_BITS 8
#endif
// This is how often we'll perform a phase advance, as well as ADC sampling
// rate. The higher this value, the smoother the output wave will be, at the
// expense of CPU time. It maxes out around 62000 (TBD)
// May be overridden in the sketch to improve performance
#ifndef DDS_REFCLK_DEFAULT
#define DDS_REFCLK_DEFAULT 9600
#endif
// As each Arduino crystal is a little different, this can be fine tuned to
// provide more accurate frequencies. Adjustments in the range of hundreds
// is a good start.
#ifndef DDS_REFCLK_OFFSET
#define DDS_REFCLK_OFFSET 0
#endif
#ifdef DDS_USE_ONLY_TIMER2
// TODO: Figure out where this clock value is generated from
#define DDS_REFCLK_DEFAULT (62500/4)
#endif
// Output some of the calculations and information about the DDS over serial
//#define DDS_DEBUG_SERIAL
// When defined, use the 1024 element sine lookup table. This improves phase
// accuracy, at the cost of more flash and CPU requirements.
// #define DDS_TABLE_LARGE
#ifdef DDS_TABLE_LARGE
// How many bits to keep from the accumulator to look up in this table
#define ACCUMULATOR_BIT_SHIFT (ACCUMULATOR_BITS-10)
static const int8_t ddsSineTable[1024] PROGMEM = {
0, 0, 1, 2, 3, 3, 4, 5, 6, 7, 7, 8, 9, 10, 10, 11, 12, 13, 13, 14, 15, 16, 17, 17, 18, 19, 20, 20, 21, 22, 23, 24,
24, 25, 26, 27, 27, 28, 29, 30, 30, 31, 32, 33, 33, 34, 35, 36, 36, 37, 38, 39, 39, 40, 41, 42, 42, 43, 44, 44, 45, 46, 47, 47,
48, 49, 50, 50, 51, 52, 52, 53, 54, 55, 55, 56, 57, 57, 58, 59, 59, 60, 61, 61, 62, 63, 63, 64, 65, 65, 66, 67, 67, 68, 69, 69,
70, 71, 71, 72, 73, 73, 74, 75, 75, 76, 76, 77, 78, 78, 79, 79, 80, 81, 81, 82, 82, 83, 84, 84, 85, 85, 86, 87, 87, 88, 88, 89,
89, 90, 90, 91, 91, 92, 93, 93, 94, 94, 95, 95, 96, 96, 97, 97, 98, 98, 99, 99, 100, 100, 101, 101, 102, 102, 102, 103, 103, 104, 104, 105,
105, 106, 106, 106, 107, 107, 108, 108, 108, 109, 109, 110, 110, 110, 111, 111, 112, 112, 112, 113, 113, 113, 114, 114, 114, 115, 115, 115, 116, 116, 116, 117,
117, 117, 117, 118, 118, 118, 119, 119, 119, 119, 120, 120, 120, 120, 121, 121, 121, 121, 121, 122, 122, 122, 122, 123, 123, 123, 123, 123, 123, 124, 124, 124,
124, 124, 124, 124, 125, 125, 125, 125, 125, 125, 125, 125, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126,
127, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 126, 125, 125, 125, 125, 125, 125, 125, 125, 124, 124, 124,
124, 124, 124, 124, 123, 123, 123, 123, 123, 123, 122, 122, 122, 122, 121, 121, 121, 121, 121, 120, 120, 120, 120, 119, 119, 119, 119, 118, 118, 118, 117, 117,
117, 117, 116, 116, 116, 115, 115, 115, 114, 114, 114, 113, 113, 113, 112, 112, 112, 111, 111, 110, 110, 110, 109, 109, 108, 108, 108, 107, 107, 106, 106, 106,
105, 105, 104, 104, 103, 103, 102, 102, 102, 101, 101, 100, 100, 99, 99, 98, 98, 97, 97, 96, 96, 95, 95, 94, 94, 93, 93, 92, 91, 91, 90, 90,
89, 89, 88, 88, 87, 87, 86, 85, 85, 84, 84, 83, 82, 82, 81, 81, 80, 79, 79, 78, 78, 77, 76, 76, 75, 75, 74, 73, 73, 72, 71, 71,
70, 69, 69, 68, 67, 67, 66, 65, 65, 64, 63, 63, 62, 61, 61, 60, 59, 59, 58, 57, 57, 56, 55, 55, 54, 53, 52, 52, 51, 50, 50, 49,
48, 47, 47, 46, 45, 44, 44, 43, 42, 42, 41, 40, 39, 39, 38, 37, 36, 36, 35, 34, 33, 33, 32, 31, 30, 30, 29, 28, 27, 27, 26, 25,
24, 24, 23, 22, 21, 20, 20, 19, 18, 17, 17, 16, 15, 14, 13, 13, 12, 11, 10, 10, 9, 8, 7, 7, 6, 5, 4, 3, 3, 2, 1, 0,
0, 0, -1, -2, -3, -3, -4, -5, -6, -7, -7, -8, -9, -10, -10, -11, -12, -13, -13, -14, -15, -16, -17, -17, -18, -19, -20, -20, -21, -22, -23, -24,
-24, -25, -26, -27, -27, -28, -29, -30, -30, -31, -32, -33, -33, -34, -35, -36, -36, -37, -38, -39, -39, -40, -41, -42, -42, -43, -44, -44, -45, -46, -47, -47,
-48, -49, -50, -50, -51, -52, -52, -53, -54, -55, -55, -56, -57, -57, -58, -59, -59, -60, -61, -61, -62, -63, -63, -64, -65, -65, -66, -67, -67, -68, -69, -69,
-70, -71, -71, -72, -73, -73, -74, -75, -75, -76, -76, -77, -78, -78, -79, -79, -80, -81, -81, -82, -82, -83, -84, -84, -85, -85, -86, -87, -87, -88, -88, -89,
-89, -90, -90, -91, -91, -92, -93, -93, -94, -94, -95, -95, -96, -96, -97, -97, -98, -98, -99, -99, -100, -100, -101, -101, -102, -102, -102, -103, -103, -104, -104, -105,
-105, -106, -106, -106, -107, -107, -108, -108, -108, -109, -109, -110, -110, -110, -111, -111, -112, -112, -112, -113, -113, -113, -114, -114, -114, -115, -115, -115, -116, -116, -116, -117,
-117, -117, -117, -118, -118, -118, -119, -119, -119, -119, -120, -120, -120, -120, -121, -121, -121, -121, -121, -122, -122, -122, -122, -123, -123, -123, -123, -123, -123, -124, -124, -124,
-124, -124, -124, -124, -125, -125, -125, -125, -125, -125, -125, -125, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126,
-127, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -126, -125, -125, -125, -125, -125, -125, -125, -125, -124, -124, -124,
-124, -124, -124, -124, -123, -123, -123, -123, -123, -123, -122, -122, -122, -122, -121, -121, -121, -121, -121, -120, -120, -120, -120, -119, -119, -119, -119, -118, -118, -118, -117, -117,
-117, -117, -116, -116, -116, -115, -115, -115, -114, -114, -114, -113, -113, -113, -112, -112, -112, -111, -111, -110, -110, -110, -109, -109, -108, -108, -108, -107, -107, -106, -106, -106,
-105, -105, -104, -104, -103, -103, -102, -102, -102, -101, -101, -100, -100, -99, -99, -98, -98, -97, -97, -96, -96, -95, -95, -94, -94, -93, -93, -92, -91, -91, -90, -90,
-89, -89, -88, -88, -87, -87, -86, -85, -85, -84, -84, -83, -82, -82, -81, -81, -80, -79, -79, -78, -78, -77, -76, -76, -75, -75, -74, -73, -73, -72, -71, -71,
-70, -69, -69, -68, -67, -67, -66, -65, -65, -64, -63, -63, -62, -61, -61, -60, -59, -59, -58, -57, -57, -56, -55, -55, -54, -53, -52, -52, -51, -50, -50, -49,
-48, -47, -47, -46, -45, -44, -44, -43, -42, -42, -41, -40, -39, -39, -38, -37, -36, -36, -35, -34, -33, -33, -32, -31, -30, -30, -29, -28, -27, -27, -26, -25,
-24, -24, -23, -22, -21, -20, -20, -19, -18, -17, -17, -16, -15, -14, -13, -13, -12, -11, -10, -10, -9, -8, -7, -7, -6, -5, -4, -3, -3, -2, -1, 0
};
#else
#define ACCUMULATOR_BIT_SHIFT (ACCUMULATOR_BITS-8)
static const int8_t ddsSineTable[256] PROGMEM = {
0, 3, 6, 9, 12, 16, 19, 22, 25, 28, 31, 34, 37, 40, 43, 46, 49,
51, 54, 57, 60, 63, 65, 68, 71, 73, 76, 78, 81, 83, 85, 88, 90,
92, 94, 96, 98, 100, 102, 104, 106, 107, 109, 111, 112, 113, 115,
116, 117, 118, 120, 121, 122, 122, 123, 124, 125, 125, 126, 126,
126, 127, 127, 127, 127, 127, 127, 127, 126, 126, 126, 125, 125,
124, 123, 122, 122, 121, 120, 118, 117, 116, 115, 113, 112, 111,
109, 107, 106, 104, 102, 100, 98, 96, 94, 92, 90, 88, 85, 83, 81,
78, 76, 73, 71, 68, 65, 63, 60, 57, 54, 51, 49, 46, 43, 40, 37,
34, 31, 28, 25, 22, 19, 16, 12, 9, 6, 3, 0, -3, -6, -9, -12, -16,
-19, -22, -25, -28, -31, -34, -37, -40, -43, -46, -49, -51, -54,
-57, -60, -63, -65, -68, -71, -73, -76, -78, -81, -83, -85, -88,
-90, -92, -94, -96, -98, -100, -102, -104, -106, -107, -109, -111,
-112, -113, -115, -116, -117, -118, -120, -121, -122, -122, -123,
-124, -125, -125, -126, -126, -126, -127, -127, -127, -127, -127,
-127, -127, -126, -126, -126, -125, -125, -124, -123, -122, -122,
-121, -120, -118, -117, -116, -115, -113, -112, -111, -109, -107,
-106, -104, -102, -100, -98, -96, -94, -92, -90, -88, -85, -83,
-81, -78, -76, -73, -71, -68, -65, -63, -60, -57, -54, -51, -49,
-46, -43, -40, -37, -34, -31, -28, -25, -22, -19, -16, -12, -9, -6, -3
};
#endif /* DDS_TABLE_LARGE */
class DDS {
public:
DDS(): refclk(DDS_REFCLK_DEFAULT), refclkOffset(DDS_REFCLK_OFFSET),
accumulator(0), running(false),
timeLimited(false), tickDuration(0), amplitude(255)
{};
// Start all of the timers needed
void start();
// Is the DDS presently producing a tone?
const bool isRunning() { return running; };
// Stop the DDS timers
void stop();
// Start and stop the PWM output
void on() {
timeLimited = false;
running = true;
}
// Provide a duration in ms for the tone
void on(unsigned short duration) {
// Duration in ticks from milliseconds is:
// t = (1/refclk)
tickDuration = (unsigned long)((unsigned long)duration * (unsigned long)refclk) / 1000;
timeLimited = true;
running = true;
}
void off() {
running = false;
}
// Generate a tone for a specific amount of time
void play(unsigned short freq, unsigned short duration) {
setFrequency(freq);
on(duration);
}
// Blocking version
void playWait(unsigned short freq, unsigned short duration) {
play(freq, duration);
delay(duration);
}
// Use these to get some calculated values for specific frequencies
// or to get the current frequency stepping rate.
ddsAccumulator_t calcFrequency(unsigned short freq);
ddsAccumulator_t getPhaseAdvance() { return stepRate; };
// Our maximum clock isn't very high, so our highest
// frequency supported will fit in a short.
void setFrequency(unsigned short freq) { stepRate = calcFrequency(freq); };
void setPrecalcFrequency(ddsAccumulator_t freq) { stepRate = freq; };
// Handle phase shifts
void setPhaseDeg(int16_t degrees);
void changePhaseDeg(int16_t degrees);
// Adjustable reference clock. This shoud be done before the timers are
// started, or they will need to be restarted. Frequencies will need to
// be set again to use the new clock.
void setReferenceClock(unsigned long ref) {
refclk = ref;
}
unsigned long getReferenceClock() {
return refclk;
}
void setReferenceOffset(int16_t offset) {
refclkOffset = offset;
}
int16_t getReferenceOffset() {
return refclkOffset;
}
uint8_t getDutyCycle();
// Set a scaling factor. To keep things quick, this is a power of 2 value.
// Set it with 0 for lowest (which will be off), 8 is highest.
void setAmplitude(unsigned char amp) {
amplitude = amp;
}
// This is the function called by the ADC_vect ISR to produce the tones
void clockTick();
private:
volatile bool running;
volatile unsigned long tickDuration;
volatile bool timeLimited;
volatile unsigned char amplitude;
volatile ddsAccumulator_t accumulator;
volatile ddsAccumulator_t stepRate;
ddsAccumulator_t refclk;
int16_t refclkOffset;
static DDS *sDDS;
};
#endif /* _DDS_H_ */

1471
HamShield.cpp Normal file

File diff suppressed because it is too large Load Diff

View File

@ -2,25 +2,42 @@
// Based on Programming Manual rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
// 11/22/2013 by Morgan Redfield <redfieldm@gmail.com>
// 04/26/2015 various changes Casey Halverson <spaceneedle@gmail.com>
// 05/08/2017 CTCSS code added
#ifndef _HAMSHIELD_H_
#define _HAMSHIELD_H_
#include "HamShield_comms.h"
#include "SimpleFIFO.h"
#include "AFSK.h"
#include "DDS.h"
#include <avr/pgmspace.h>
// HamShield constants
#define HAMSHIELD_MORSE_DOT 100 // Morse code dot length (smaller is faster WPM)
#define HAMSHIELD_MORSE_BUFFER_SIZE 80 // Char buffer size for morse code text
#define HAMSHIELD_AUX_BUTTON 2 // Pin assignment for AUX button
#define HAMSHIELD_PWM_PIN 3 // Pin assignment for PWM output
#define HAMSHIELD_EMPTY_CHANNEL_RSSI -110 // Default threshold where channel is considered "clear"
#define HAMSHIELD_AFSK_RX_FIFO_LEN 16
// button modes
#define PTT_MODE 1
#define RESET_MODE 2
// Device Constants
#define A1846S_DEV_ADDR_SENHIGH 0b0101110
#define A1846S_DEV_ADDR_SENLOW 0b1110001
// Device Registers
#define A1846S_CTL_REG 0x30 // control register
#define A1846S_CLK_MODE_REG 0x04 // clk_mode
#define A1846S_PABIAS_REG 0x0A // control register for bias voltage
//#define A1846S_BAND_SEL_REG 0x0F // band_sel register <1:0>
#define A1846S_FLAG_REG 0x1C
#define A1846S_GPIO_MODE_REG 0x1F // GPIO mode select register
#define A1846S_FREQ_HI_REG 0x29 // freq<29:16>
#define A1846S_FREQ_LO_REG 0x2A // freq<15:0>
@ -28,27 +45,30 @@
//#define A1846S_ADCLK_FREQ_REG 0x2C // adclk_freq<15:0>
#define A1846S_INT_MODE_REG 0x2D // interrupt enables
#define A1846S_TX_VOICE_REG 0x3A // tx voice control reg
#define A1846S_TH_H_VOX_REG 0x64 // register holds vox high (open) threshold bits
#define A1846S_TH_L_VOX_REG 0x64 // register holds vox low (shut) threshold bits
#define A1846S_TH_H_VOX_REG 0x41 // register holds vox high (open) threshold bits
#define A1846S_TH_L_VOX_REG 0x42 // register holds vox low (shut) threshold bits
#define A1846S_FM_DEV_REG 0x43 // register holds fm deviation settings
#define A1846S_RX_VOLUME_REG 0x44 // register holds RX volume settings
#define A1846S_SQ_OPEN_THRESH_REG 0x49 // see sq
#define A1846S_SUBAUDIO_REG 0x45 // sub audio register
#define A1846S_SQ_OPEN_THRESH_REG 0x48 // see sq
#define A1846S_SQ_SHUT_THRESH_REG 0x49 // see sq
#define A1846S_CTCSS_FREQ_REG 0x4A // ctcss_freq<15:0>
#define A1846S_CDCSS_CODE_HI_REG 0x4B // cdcss_code<23:16>
#define A1846S_CDCSS_CODE_LO_REG 0x4C // cdccs_code<15:0>
#define A1846S_CTCSS_MODE_REG 0x4e // see ctcss
#define A1846S_SQ_OUT_SEL_REG 0x54 // see sq
#define A1846S_FILTER_REG 0x58
#define A1846S_CTCSS_THRESH_REG 0x5B
#define A1846S_EMPH_FILTER_REG 0x58
#define A1846S_FLAG_REG 0x5C // holds flags for different statuses
#define A1846S_RSSI_REG 0x1B // holds RSSI (unit 1dB)
#define A1846S_VSSI_REG 0x1A // holds VSSI (unit mV)
#define A1846S_DTMF_CTL_REG 0x63 // see dtmf
#define A1846S_DTMF_C01_REG 0x66 // holds frequency value for c0 and c1
#define A1846S_DTMF_C23_REG 0x67 // holds frequency value for c2 and c3
#define A1846S_DTMF_C45_REG 0x68 // holds frequency value for c4 and c5
#define A1846S_DTMF_C67_REG 0x69 // holds frequency value for c6 and c7
#define A1846S_DTMF_RX_REG 0x6C // received dtmf signal
// NOTE: could add registers and bitfields for dtmf tones, is this necessary?
#define A1846S_DTMF_ENABLE_REG 0x7A // holds dtmf_enable
#define A1846S_DTMF_CODE_REG 0x7E // holds dtmf_sample and dtmf_code
#define A1846S_TONE1_FREQ 0x35 // holds frequency of tone 1 (in 0.1Hz increments)
#define A1846S_TONE2_FREQ 0x36 // holds frequency of tone 2 (in 0.1Hz increments)
#define A1846S_DTMF_TIME_REG 0x7B // holds time intervals for DTMF
// Device Bit Fields
@ -81,31 +101,32 @@
//#define A1846S_BAND_SEL_BIT 7 // band_sel<1:0>
//#define A1846S_BAND_SEL_LENGTH 2
// Bitfields for A1846_GPIO_MODE_REG
#define A1846S_GPIO7_MODE_BIT 15 // <1:0> 00=hi-z,01=vox,10=low,11=hi
#define A1846S_GPIO7_MODE_LENGTH 2
#define A1846S_GPIO6_MODE_BIT 13 // <1:0> 00=hi-z,01=sq or =sq&ctcss/cdcss when sq_out_sel=1,10=low,11=hi
#define A1846S_GPIO6_MODE_LENGTH 2
#define A1846S_GPIO5_MODE_BIT 11 // <1:0> 00=hi-z,01=txon_rf,10=low,11=hi
#define A1846S_GPIO5_MODE_LENGTH 2
#define A1846S_GPIO4_MODE_BIT 9 // <1:0> 00=hi-z,01=rxon_rf,10=low,11=hi
#define A1846S_GPIO4_MODE_LENGTH 2
#define A1846S_GPIO3_MODE_BIT 7 // <1:0> 00=hi-z,01=sdo,10=low,11=hi
#define A1846S_GPIO3_MODE_LENGTH 2
#define A1846S_GPIO2_MODE_BIT 5 // <1:0> 00=hi-z,01=int,10=low,11=hi
#define A1846S_GPIO2_MODE_LENGTH 2
#define A1846S_GPIO1_MODE_BIT 3 // <1:0> 00=hi-z,01=code_out/code_in,10=low,11=hi
#define A1846S_GPIO1_MODE_LENGTH 2
#define A1846S_GPIO0_MODE_BIT 1 // <1:0> 00=hi-z,01=css_out/css_in/css_cmp,10=low,11=hi
#define A1846S_GPIO0_MODE_LENGTH 2
// Bitfields for RDA1864_GPIO_MODE_REG
#define RDA1864_GPIO7_MODE_BIT 15 // <1:0> 00=hi-z,01=vox,10=low,11=hi
#define RDA1864_GPIO7_MODE_LENGTH 2
#define RDA1864_GPIO6_MODE_BIT 13 // <1:0> 00=hi-z,01=sq or =sq&ctcss/cdcss when sq_out_sel=1,10=low,11=hi
#define RDA1864_GPIO6_MODE_LENGTH 2
#define RDA1864_GPIO5_MODE_BIT 11 // <1:0> 00=hi-z,01=txon_rf,10=low,11=hi
#define RDA1864_GPIO5_MODE_LENGTH 2
#define RDA1864_GPIO4_MODE_BIT 9 // <1:0> 00=hi-z,01=rxon_rf,10=low,11=hi
#define RDA1864_GPIO4_MODE_LENGTH 2
#define RDA1864_GPIO3_MODE_BIT 7 // <1:0> 00=hi-z,01=sdo,10=low,11=hi
#define RDA1864_GPIO3_MODE_LENGTH 2
#define RDA1864_GPIO2_MODE_BIT 5 // <1:0> 00=hi-z,01=int,10=low,11=hi
#define RDA1864_GPIO2_MODE_LENGTH 2
#define RDA1864_GPIO1_MODE_BIT 3 // <1:0> 00=hi-z,01=code_out/code_in,10=low,11=hi
#define RDA1864_GPIO1_MODE_LENGTH 2
#define RDA1864_GPIO0_MODE_BIT 1 // <1:0> 00=hi-z,01=css_out/css_in/css_cmp,10=low,11=hi
#define RDA1864_GPIO0_MODE_LENGTH 2
// Bitfields for A1846S_INT_MODE_REG
#define A1846S_CSS_CMP_INT_BIT 9 // css_cmp_uint16_t enable
#define A1846S_RXON_RF_INT_BIT 8 // rxon_rf_uint16_t enable
#define A1846S_TXON_RF_INT_BIT 7 // txon_rf_uint16_t enable
#define A1846S_DTMF_IDLE_INT_BIT 6 // dtmf_idle_uint16_t enable
#define A1846S_CTCSS_PHASE_INT_BIT 5 // ctcss phase shift detect uint16_t enable
#define A1846S_IDLE_TIMEOUT_INT_BIT 4 // idle state time out uint16_t enable
#define A1846S_RXON_RF_TIMEOUT_INT_BIT 3 // rxon_rf timerout uint16_t enable
#define A1846S_RXON_RF_TIMeOUT_INT_BIT 3 // rxon_rf timerout uint16_t enable
#define A1846S_SQ_INT_BIT 2 // sq uint16_t enable
#define A1846S_TXON_RF_TIMEOUT_INT_BIT 1 // txon_rf time out uint16_t enable
#define A1846S_VOX_INT_BIT 0 // vox uint16_t enable
@ -113,15 +134,10 @@
// Bitfields for A1846S_TX_VOICE_REG
#define A1846S_VOICE_SEL_BIT 14 //voice_sel<1:0>
#define A1846S_VOICE_SEL_LENGTH 3
#define A1846S_CTCSS_DET_BIT 5
// Bitfields for A1846S_TH_H_VOX_REG
#define A1846S_TH_H_VOX_BIT 13 // th_h_vox<13:7>
#define A1846S_TH_H_VOX_LEN 7
// Bitfields for A1846S_TH_L_VOX_REG
#define A1846S_TH_L_VOX_BIT 6 // th_l_vox<6:0>
#define A1846S_TH_L_VOX_LEN 7
#define A1846S_TH_H_VOX_BIT 14 // th_h_vox<14:0>
#define A1846S_TH_H_VOX_LENGTH 15
// Bitfields for A1846S_FM_DEV_REG
#define A1846S_FM_DEV_VOICE_BIT 12 // CTCSS/CDCSS and voice deviation <6:0>
@ -135,69 +151,90 @@
#define A1846S_RX_VOL_2_BIT 3 // volume 2 <3:0>, (0000)-15dB~(1111)0dB, step 1dB
#define A1846S_RX_VOL_2_LENGTH 4
// Bitfields for Sub Audio Bits
#define A1846S_CTDCSS_OUT_SEL_BIT 5
#define A1846S_CTDCSS_DTEN_BIT 4
#define A1846S_CTDCSS_DTEN_LEN 5
#define A1846S_CDCSS_SEL_BIT 6 // cdcss_sel
#define A1846S_CDCSS_INVERT_BIT 6 // cdcss_sel
#define A1846S_SHIFT_SEL_BIT 15
#define A1846S_SHIFT_SEL_LEN 2
// Bitfields for A1846S_SUBAUDIO_REG Sub Audio Register
#define A1846S_SHIFT_SEL_BIT 15 // shift_sel<1:0> see eliminating tail noise
#define A1846S_SHIFT_SEL_LENGTH 2
#define A1846S_POS_DET_EN_BIT 11 // if 1, cdcss code will be detected
#define A1846S_CSS_DET_EN_BIT 10 // 1 - sq detect will add ctcss/cdcss detect result and control voice output on or off
#define A1846S_NEG_DET_EN_BIT 7 // if 1, cdcss inverse code will be detected at same time
#define A1846S_CDCSS_SEL_BIT 4 // cdcss_sel
#define A1846S_CTCSS_SEL_BIT 3 // ctcss_sel
#define A1846S_C_MODE_BIT 2 // c_mode<2:0>
#define A1846S_C_MODE_LENGTH 3
// Bitfields for A1846S_SQ_THRESH_REG
#define A1846S_SQ_OPEN_THRESH_BIT 13 // sq open threshold <6:0>
#define A1846S_SQ_OPEN_THRESH_LENGTH 7
#define A1846S_SQ_OPEN_THRESH_BIT 9 // sq open threshold <9:0>
#define A1846S_SQ_OPEN_THRESH_LENGTH 10
// Bitfields for A1846S_SQ_SHUT_THRESH_REG
#define A1846S_SQ_SHUT_THRESH_BIT 6 // sq shut threshold <6:0>
#define A1846S_SQ_SHUT_THRESH_LENGTH 7
#define A1846S_SQ_SHUT_THRESH_BIT 9 // sq shut threshold <9:0>
#define A1846S_SQ_SHUT_THRESH_LENGTH 10
// Bitfields for A1846S_SQ_OUT_SEL_REG
#define A1846S_SQ_OUT_SEL_BIT 7 // sq_out_sel
// Bitfields for A1846S_FILTER_REG
#define A1846S_VXHPF_FILTER_EN 11
#define A1846S_VXLPF_FILTER_EN 12
#define A1846S_EMPH_FILTER_EN 7
#define A1846S_VHPF_FILTER_EN 6
#define A1846S_VLPF_FILTER_EN 5
#define A1846S_CTCSS_FILTER_BYPASS 3
// Bitfields for A1846S_EMPH_FILTER_REG
#define A1846S_EMPH_FILTER_EN 3
// Bitfields for A1846S_FLAG_REG
#define A1846S_CTCSS1_FLAG_BIT 9 // 1 when rxon is enabled
#define A1846S_CTCSS2_FLAG_BIT 8 // 1 when txon is enabled
#define A1846S_DTMF_IDLE_FLAG_BIT 12 // dtmf idle flag
#define A1846S_RXON_RF_FLAG_BIT 10 // 1 when rxon is enabled
#define A1846S_TXON_RF_FLAG_BIT 9 // 1 when txon is enabled
#define A1846S_INVERT_DET_FLAG_BIT 7 // ctcss phase shift detect
#define A1846S_CSS_CMP_FLAG_BIT 2 // ctcss/cdcss compared
#define A1846S_SQ_FLAG_BIT 0 // sq final signal out from dsp
#define A1846S_VOX_FLAG_BIT 1 // vox out from dsp
#define A1846S_SQ_FLAG_BIT 1 // sq final signal out from dsp
#define A1846S_VOX_FLAG_BIT 0 // vox out from dsp
// Bitfields for A1846S_RSSI_REG
#define A1846S_RSSI_BIT 15 // RSSI readings <7:0>
#define A1846S_RSSI_LENGTH 8
// Bitfields for A1846S_VSSI_REG
#define A1846S_VSSI_BIT 15 // voice signal strength indicator <7:0> (unit 0.5dB)
#define A1846S_VSSI_LENGTH 8
#define A1846S_MSSI_BIT 7 // mic signal strength <7:0> (unit 0.5 dB)
#define A1846S_MSSI_LENGTH 8
#define A1846S_VSSI_BIT 14 // voice signal strength indicator <14:0> (unit mV)
#define A1846S_VSSI_LENGTH 15
// Bitfields for A1846S_DTMF_ENABLE_REG
#define A1846S_DTMF_ENABLE_BIT 15
#define A1846S_TONE_DETECT 14
#define A18462_DTMF_DET_TIME_BIT 7
#define A18462_DTMF_DET_TIME_LEN 8
// Bitfields for A1846S_DTMF_CTL_REG
#define A1846S_DTMF_MODE_BIT 9 //
#define A1846S_DTMF_MODE_LENGTH 2
#define A1846S_DTMF_EN_BIT 8 // enable dtmf
#define A1846S_DTMF_TIME1_BIT 7 // dtmf time 1 <3:0>
#define A1846S_DTMF_TIME1_LENGTH 4
#define A1846S_DTMF_TIME2_BIT 3 // dtmf time 2 <3:0>
#define A1846S_DTMF_TIME2_LENGTH 4
// Bitfields for A1846S_DTMF_SAMPLE_REG
#define A1846S_DTMF_SAMPLE_BIT 4
#define A1846S_DTMF_CODE_BIT 3
#define A1846S_DTMF_CODE_LEN 4
#define A1846S_DTMF_TX_IDLE_BIT 5
// Bitfields for A1846S_DTMF_RX_REG
#define A1846S_DTMF_INDEX_BIT 10 // dtmf index <5:3> - tone 1 detect index, <2:0> - tone 2 detect index
#define A1846S_DTMF_INDEX_LENGTH 6
#define A1846S_DTMF_TONE1_IND_BIT 10
#define A1846S_DTMF_TONE1_IND_LENGTH 3
#define A1846S_DTMF_TONE2_IND_BIT 7
#define A1846S_DTMF_TONE2_IND_LENGTH 3
#define A1846S_DTMF_FLAG_BIT 4
#define A1846S_DTMF_CODE_BIT 3 // dtmf code out <3:0>
#define A1846S_DTMF_CODE_LENGTH 4
// dtmf code out
// 1:f0+f4, 2:f0+f5, 3:f0+f6, A:f0+f7,
// 4:f1+f4, 5:f1+f5, 6:f1+f6, B:f1+f7,
// 7:f2+f4, 8:f2+f5, 9:f2+f6, C:f2+f7,
// E(*):f3+f4, 0:f3+f5, F(#):f3+f6, D:f3+f7
// Bitfields for A1846S_DTMF_TIME_REG
#define A1846S_DUALTONE_TX_TIME_BIT 5 // duration of dual tone TX (via DTMF) in 2.5ms increments
#define A1846S_DUALTONE_TX_TIME_LEN 6
#define A1846S_DTMF_IDLE_TIME_BIT 11
#define A1846S_DTMF_IDLE_TIME_LEN 6
// Bitfields for DTMF registers
#define A1846S_DTMF_C0_BIT 15
#define A1846S_DTMF_C0_LENGTH 8
#define A1846S_DTMF_C1_BIT 7
#define A1846S_DTMF_C1_LENGTH 8
#define A1846S_DTMF_C2_BIT 15
#define A1846S_DTMF_C2_LENGTH 8
#define A1846S_DTMF_C3_BIT 7
#define A1846S_DTMF_C3_LENGTH 8
#define A1846S_DTMF_C4_BIT 15
#define A1846S_DTMF_C4_LENGTH 8
#define A1846S_DTMF_C5_BIT 7
#define A1846S_DTMF_C5_LENGTH 8
#define A1846S_DTMF_C6_BIT 15
#define A1846S_DTMF_C6_LENGTH 8
#define A1846S_DTMF_C7_BIT 7
#define A1846S_DTMF_C7_LENGTH 8
// SSTV VIS Codes
@ -217,29 +254,16 @@
#define HAMSHIELD_PSK31_FREQ 1000
// Morse Configuration
#define MORSE_FREQ 600
#define MORSE_DOT 150 // ms
#define SYMBOL_END_TIME 5 //millis
#define CHAR_END_TIME (MORSE_DOT*2.7)
#define MESSAGE_END_TIME (MORSE_DOT*8)
#define MIN_DOT_TIME (MORSE_DOT-30)
#define MAX_DOT_TIME (MORSE_DOT+55)
#define MIN_DASH_TIME (MORSE_DOT*3-30)
#define MAX_DASH_TIME (MORSE_DOT*3+55)
class HamShield {
public:
HamShield(uint8_t ncs_pin = nCS, uint8_t clk_pin = CLK, uint8_t dat_pin = DAT, uint8_t mic_pin = MIC);
// public singleton for ISRs to reference
static HamShield *sHamShield; // HamShield singleton, used for ISRs mostly
HamShield();
HamShield(uint8_t address);
void initialize(); // defaults to 12.5kHz
void initialize(bool narrowBand); // select 12.5kHz if true or 25kHz if false
void setupWideBand();
void setupNarrowBand();
void initialize();
bool testConnection();
// read control reg
@ -251,19 +275,15 @@ class HamShield {
void safeMode();
bool frequency(uint32_t freq_khz);
bool frequency_float(float freq_khz);
uint32_t getFrequency();
float getFrequency_float();
/* ToDo
// channel mode
// 11 - 25kHz channel
// 00 - 12.5kHz channel
// 10,01 - reserved
void setChanMode(uint16_t mode);
uint16_t getChanMode();
*/
void setModeTransmit(); // turn off rx, turn on tx
void setModeReceive(); // turn on rx, turn off tx
void setModeOff(); // turn off rx, turn off tx, set pwr_dwn bit
@ -281,7 +301,6 @@ class HamShield {
void setTxSourceNone();
uint16_t getTxSource();
/*
// PA bias voltage is unused (maybe remove this)
// set PA_bias voltage
// 000000: 1.01V
@ -294,45 +313,29 @@ class HamShield {
// 1111111:3.13V
void setPABiasVoltage(uint16_t voltage);
uint16_t getPABiasVoltage();
*/
// Subaudio settings
// Ctcss/cdcss mode sel
// x00=disable,
// 001=inner ctcss en,
// 010= inner cdcss en
// 101= outer ctcss en,
// 110=outer cdcss en
// others =disable
void setCtcssCdcssMode(uint16_t mode);
uint16_t getCtcssCdcssMode();
void setDetPhaseShift();
void setDetInvertCdcss();
void setDetCdcss();
void setDetCtcss();
void setInnerCtcssMode();
void setInnerCdcssMode();
void setOuterCtcssMode();
void setOuterCdcssMode();
void disableCtcssCdcss();
// ctcss settings
void setCtcss(float freq_Hz);
void setCtcssFreq(uint16_t freq_milliHz);
uint16_t getCtcssFreqMilliHz();
float getCtcssFreqHz();
void setCtcssFreqToStandard(); // freq must be 134.4Hz for standard cdcss mode
void enableCtcssTx();
void enableCtcssRx();
void enableCtcss();
void disableCtcssTx();
void disableCtcssRx();
void disableCtcss();
void setCtcssDetThreshIn(uint8_t thresh);
uint8_t getCtcssDetThreshIn();
void setCtcssDetThreshOut(uint8_t thresh);
uint8_t getCtcssDetThreshOut();
bool getCtcssToneDetected();
// Ctcss_sel
// 1 = ctcss_cmp/cdcss_cmp out via gpio
// 0 = ctcss/cdcss sdo out vio gpio
void setCtcssGpioSel(bool cmp_nsdo);
bool getCtcssGpioSel();
void setCdcssInvert(bool invert);
bool getCdcssInvert();
void setCtcssSel(bool cmp_nsdo);
bool getCtcssSel();
// Cdcss_sel
// 1 = long (24 bit) code
@ -340,18 +343,30 @@ class HamShield {
void setCdcssSel(bool long_nshort);
bool getCdcssSel();
// Cdcss neg_det_en
void enableCdcssNegDet();
void disableCdcssNegDet();
bool getCdcssNegDetEnabled();
// Cdcss pos_det_en
void enableCdcssPosDet();
void disableCdcssPosDet();
bool getCdcssPosDetEnabled();
// ctss_det_en
bool getCtssDetEnabled();
// css_det_en
void enableCssDet();
void disableCssDet();
bool getCssDetEnabled();
// ctcss freq
void setCtcss(float freq);
void setCtcssFreq(uint16_t freq);
uint16_t getCtcssFreq();
void setCtcssFreqToStandard(); // freq must be 134.4Hz for standard cdcss mode
// cdcss codes
void setCdcssCode(uint16_t code);
uint16_t getCdcssCode();
// SQ
void setSQOn();
void setSQOff();
@ -362,7 +377,6 @@ class HamShield {
int16_t getSQHiThresh();
void setSQLoThresh(int16_t sq_lo_threshold); // Sq detect low th, rssi_cmp will be 0 when rssi<th_l_sq && time delay meet, unit 1dB
int16_t getSQLoThresh();
bool getSquelching();
// SQ out select
void setSQOutSel();
@ -395,37 +409,23 @@ class HamShield {
uint16_t getShiftSelect();
// DTMF
// Reading a single DTMF code:
// enableDTMFReceive()
// while (getDTMFSample() == 0) { delay(10); }
// uint16_t code = getDTMFCode();
// while (getDTMFSample() == 1) { delay(10); }
// disableDTMF();
// Writing a single DTMF code:
// setDTMFCode(code); // code is a uint16_t from 0x0 to 0xF
void enableDTMFReceive();
void setDTMFDetectTime(uint16_t detect_time);
uint16_t getDTMFDetectTime();
void setDTMFIdleTime(uint16_t idle_time); // idle time is time between DTMF Tone
uint16_t getDTMFIdleTime();
char DTMFRxLoop();
char DTMFcode2char(uint16_t code);
uint8_t DTMFchar2code(char c);
void setDTMFTxTime(uint16_t tx_time); // tx time is duration of DTMF Tone
uint16_t getDTMFTxTime();
uint16_t disableDTMF();
uint16_t getDTMFSample();
uint16_t getDTMFCode();
uint16_t getDTMFTxActive();
void setDTMFCode(uint16_t code);
void setDTMFC0(uint16_t freq);
uint16_t getDTMFC0();
void setDTMFC1(uint16_t freq);
uint16_t getDTMFC1();
void setDTMFC2(uint16_t freq);
uint16_t getDTMFC2();
void setDTMFC3(uint16_t freq);
uint16_t getDTMFC3();
void setDTMFC4(uint16_t freq);
uint16_t getDTMFC4();
void setDTMFC5(uint16_t freq);
uint16_t getDTMFC5();
void setDTMFC6(uint16_t freq);
uint16_t getDTMFC6();
void setDTMFC7(uint16_t freq);
uint16_t getDTMFC7();
// Tone
void HStone(uint8_t pin, unsigned int frequency);
void HSnoTone(uint8_t pin);
void lookForTone(uint16_t tone_hz);
uint8_t toneDetected();
// TX FM deviation
void setFMVoiceCssDeviation(uint16_t deviation);
uint16_t getFMVoiceCssDeviation();
@ -433,8 +433,6 @@ class HamShield {
uint16_t getFMCssDeviation();
// RX voice range
void setMute();
void setUnmute();
void setVolume1(uint16_t volume);
uint16_t getVolume1();
void setVolume2(uint16_t volume);
@ -447,7 +445,6 @@ class HamShield {
void setGpioLow(uint16_t gpio);
void setGpioHi(uint16_t gpio);
uint16_t getGpioMode(uint16_t gpio);
void setGpios(uint16_t mode);
uint16_t getGpios();
// Int
@ -466,27 +463,12 @@ class HamShield {
void bypassPreDeEmph();
void usePreDeEmph();
bool getPreDeEmphEnabled();
// Voice filters
void bypassVoiceHpf();
void useVoiceHpf();
bool getVoiceHpfEnabled();
void bypassVoiceLpf();
void useVoiceLpf();
bool getVoiceLpfEnabled();
// Vox filters
void bypassVoxHpf();
void useVoxHpf();
bool getVoxHpfEnabled();
void bypassVoxLpf();
void useVoxLpf();
bool getVoxLpfEnabled();
// Read Only Status Registers
int16_t readRSSI();
uint16_t readVSSI();
uint16_t readMSSI();
uint16_t readDTMFIndex(); // may want to split this into two (index1 and index2)
uint16_t readDTMFCode();
// set output power of radio
void setRfPower(uint8_t pwr);
@ -503,39 +485,38 @@ class HamShield {
uint32_t findWhitespace(uint32_t start,uint32_t stop, uint8_t dwell, uint16_t step, uint16_t threshold);
uint32_t scanChannels(uint32_t buffer[],uint8_t buffsize, uint8_t speed, uint16_t threshold);
uint32_t findWhitespaceChannels(uint32_t buffer[],uint8_t buffsize, uint8_t dwell, uint16_t threshold);
void setupMorseRx();
unsigned int getMorseFreq();
void setMorseFreq(unsigned int morse_freq_hz);
unsigned int getMorseDotMillis();
void setMorseDotMillis(unsigned int morse_dot_dur_millis);
void buttonMode(uint8_t mode);
static void isr_ptt();
static void isr_reset();
void morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]);
char morseRxLoop();
bool handleMorseTone(uint16_t tone_time, bool bits_to_process, uint8_t * rx_morse_char, uint8_t * rx_morse_bit);
char parseMorse(uint8_t rx_morse_char, uint8_t rx_morse_bit);
uint8_t morseLookup(char letter);
uint8_t morseReverseLookup(uint8_t itu);
bool waitForChannel(long timeout = 0, long breakwindow = 0, int setRSSI = HAMSHIELD_EMPTY_CHANNEL_RSSI);
bool waitForChannel(long timeout, long breakwindow, int setRSSI);
void SSTVVISCode(int code);
void SSTVTestPattern(int code);
void toneWait(uint16_t freq, long timer);
void toneWaitU(uint16_t freq, long timer);
bool parityCalc(int code);
// void AFSKOut(char buffer[80]);
// AFSK routines
bool AFSKStart();
bool AFSKEnabled() { return afsk.enabled(); }
bool AFSKStop();
bool AFSKOut(const char *);
class AFSK afsk;
private:
uint8_t devAddr;
uint8_t hs_mic_pin;
uint16_t radio_dat_buf[4];
uint16_t radio_i2c_buf[4];
bool tx_active;
bool rx_active;
float radio_frequency;
/* uint32_t FRS[];
uint32_t radio_frequency;
uint32_t FRS[];
uint32_t GMRS[];
uint32_t MURS[];
uint32_t WX[];
*/
// private utility functions
// these functions should not be called in the Arduino sketch
// just use the above public functions to do everything

97
HamShield_comms.cpp Normal file
View File

@ -0,0 +1,97 @@
/*
* Based loosely on I2Cdev by Jeff Rowberg
*/
#include "HamShield_comms.h"
int8_t HSreadBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data)
{
uint16_t b;
uint8_t count = HSreadWord(devAddr, regAddr, &b);
*data = b & (1 << bitNum);
return count;
}
int8_t HSreadBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data)
{
uint8_t count;
uint16_t w;
if ((count = HSreadWord(devAddr, regAddr, &w)) != 0) {
uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
w &= mask;
w >>= (bitStart - length + 1);
*data = w;
}
return count;
}
int8_t HSreadWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data)
{
int8_t count = 0;
uint32_t t1 = millis();
uint8_t timeout = 1000;
Wire.beginTransmission(devAddr);
Wire.write(regAddr);
Wire.endTransmission(false);
Wire.requestFrom((int)devAddr, 2); // length=words, this wants bytes
bool msb = true; // starts with MSB, then LSB
for (; Wire.available() && count < 1 && (timeout == 0 || millis() - t1 < timeout);) {
if (msb) {
// first byte is bits 15-8 (MSb=15)
data[0] = Wire.read() << 8;
} else {
// second byte is bits 7-0 (LSb=0)
data[0] |= Wire.read();
count++;
}
msb = !msb;
}
Wire.endTransmission();
if (timeout > 0 && millis() - t1 >= timeout && count < 1) count = -1; // timeout
return count;
}
bool HSwriteBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data)
{
uint16_t w;
HSreadWord(devAddr, regAddr, &w);
w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum));
return HSwriteWord(devAddr, regAddr, w);
}
bool HSwriteBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data)
{
uint16_t w;
if (HSreadWord(devAddr, regAddr, &w) != 0) {
uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
data <<= (bitStart - length + 1); // shift data into correct position
data &= mask; // zero all non-important bits in data
w &= ~(mask); // zero all important bits in existing word
w |= data; // combine data with existing word
return HSwriteWord(devAddr, regAddr, w);
} else {
return false;
}
}
bool HSwriteWord(uint8_t devAddr, uint8_t regAddr, uint16_t data)
{
uint8_t status = 0;
Wire.beginTransmission(devAddr);
Wire.write(regAddr); // send address
Wire.write((uint8_t)(data >> 8)); // send MSB
Wire.write((uint8_t)data); // send LSB
status = Wire.endTransmission();
return status == 0;
}

View File

@ -4,27 +4,8 @@
#ifndef _HAMSHIELD_COMMS_H_
#define _HAMSHIELD_COMMS_H_
#if defined(ARDUINO)
#include "Arduino.h"
#define nCS A1 //15 //
#define CLK A5 //19 //
#define DAT A4 //18 //
#define MIC 3
#else // assume Raspberry Pi
#include "stdint.h"
#include <wiringPi.h>
#include <softTone.h>
#define nCS 0 //BCM17, HW pin 11
#define CLK 3 //BCM22, HW pin 15
#define DAT 2 //BCM27, HW pin 13
#define MIC 1 //BCM18, HW pin 12
#endif
void HSsetPins(uint8_t ncs, uint8_t clk, uint8_t dat);
#include "Wire.h"
int8_t HSreadBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data);
int8_t HSreadBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data);
@ -34,12 +15,4 @@ bool HSwriteBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data
bool HSwriteBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
bool HSwriteWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
// hardware abstraction layer
unsigned long HSmillis();
void HSdelay(unsigned long ms);
void HSdelayMicroseconds(unsigned int us);
#endif /* _HAMSHIELD_COMMS_H_ */
#endif /* _HAMSHIELD_COMMS_H_ */

88
KISS.cpp Normal file
View File

@ -0,0 +1,88 @@
#include <HamShield.h>
#include "AFSK.h"
#include "KISS.h"
//AFSK::Packet kissPacket;
bool inFrame = false;
uint8_t kissBuffer[PACKET_MAX_LEN];
uint16_t kissLen = 0;
// Inside the KISS loop, we basically wait for data to come in from the
// KISS equipment, and look if we have anything to relay along
void KISS::loop() {
static bool currentlySending = false;
if(radio->afsk.decoder.read() || radio->afsk.rxPacketCount()) {
// A true return means something was put onto the packet FIFO
// If we actually have data packets in the buffer, process them all now
while(radio->afsk.rxPacketCount()) {
AFSK::Packet *packet = radio->afsk.getRXPacket();
if(packet) {
writePacket(packet);
AFSK::PacketBuffer::freePacket(packet);
}
}
}
// Check if we have incoming data to turn into a packet
while(io->available()) {
uint8_t c = (uint8_t)io->read();
if(c == KISS_FEND) {
if(inFrame && kissLen > 0) {
int i;
AFSK::Packet *packet = AFSK::PacketBuffer::makePacket(PACKET_MAX_LEN);
packet->start();
for(i = 0; i < kissLen; i++) {
packet->appendFCS(kissBuffer[i]);
}
packet->finish();
radio->afsk.encoder.putPacket(packet);
}
kissLen = 0;
inFrame = false;
}
// We're inside the boundaries of a FEND
if(inFrame) {
// Unescape the incoming data
if(c == KISS_FESC) {
c = io->read();
if(c == KISS_TFESC) {
c = KISS_FESC;
} else {
c = KISS_FEND;
}
}
kissBuffer[kissLen++] = c;
}
if(kissLen == 0 && c != KISS_FEND) {
if((c & 0xf) == 0) // First byte<3:0> should be a 0, otherwise we're having options
inFrame = true;
}
}
if(radio->afsk.txReady()) {
radio->setModeTransmit();
currentlySending = true;
if(!radio->afsk.txStart()) { // Unable to start for some reason
radio->setModeReceive();
currentlySending = false;
}
}
if(currentlySending && radio->afsk.encoder.isDone()) {
radio->setModeReceive();
currentlySending = false;
}
}
void KISS::writePacket(AFSK::Packet *p) {
int i;
io->write(KISS_FEND);
io->write((uint8_t)0); // Host to TNC port identifier
for(i = 0; i < p->len-2; i++) {
char c = p->getByte(i);
if(c == KISS_FEND || c == KISS_FESC) {
io->write(KISS_FESC);
io->write((c==KISS_FEND?KISS_TFEND:KISS_TFESC));
} else {
io->write(c);
}
}
io->write(KISS_FEND);
}

35
KISS.h Normal file
View File

@ -0,0 +1,35 @@
#ifndef _KISS_H_
#define _KISS_H_
#include <HamShield.h>
#include "AFSK.h"
#define KISS_FEND 0xC0
#define KISS_FESC 0xDB
#define KISS_TFEND 0xDC
#define KISS_TFESC 0xDD
class KISS {
public:
KISS(Stream *_io, HamShield *h, DDS *d) : io(_io), radio(h), dds(d) {}
bool read();
void writePacket(AFSK::Packet *);
void loop();
inline void isr() {
static uint8_t tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
dds->clockTick();
if(++tcnt == (DDS_REFCLK_DEFAULT/9600)) {
//PORTD |= _BV(2); // Diagnostic pin (D2)
radio->afsk.timer();
tcnt = 0;
}
//PORTD &= ~(_BV(2));
}
private:
Stream *io;
HamShield *radio;
DDS *dds;
};
#endif /* _KISS_H_ */

View File

@ -1,23 +1,31 @@
# HamShield
You can purchase HamShield (as well as smaller variants or LoRa version) at http://www.enhancedradio.com/
Please note that I2C communications are not officially supported.
The master branch is intended for use with HamShield hardware -09 and above.
The RF transciever on the HamShield has trouble driving large I2C bus capacitances (over 40pF). What this means is that it works well if the transciever is on the same physical PCB as the microcontroller (assuming good layout), but works poorly as a daughterboard.
WARNING: The dev branch is not guaranteed to work. Please use caution if you choose to use that branch.
We recommend that you use the master branch, which uses a custom communications protocol. That custom protocol does not have the same bus capacitance limitation. You're welcome to play around with I2C if you want, but it may cause instability issues.
# HamShield Arduino Library and Example Sketches
## Hardware Changes Necessary
The i2c-comms branch is not intended for use with a stock HamShield.
To use i2c communications with a HamShield 09 or above, you must first make several hardware changes to the board.
1. Remove R2
2. Short the pads of R17 (either with a wire or a low value resistor).
Then make sure that you pull the nCS pin correctly. Changing nCS changes the I2C address of the HamShield:
- nCS is logic high: A1846S_DEV_ADDR_SENHIGH 0b0101110
- nCS is logic low: A1846S_DEV_ADDR_SENLOW 0b1110001
HamShield Arduino Library and Example Sketches
This repository is meant to be checked out into your Arduino application's libraries folder. After reloading the application, the library and example sketches should be available for use.
For overview, help, tricks, tips, and more, check out the wiki:
https://github.com/EnhancedRadioDevices/HamShield/wiki
# KISS and AFSK
We've moved the KISS and AFSK code to a separate library to help keep memory usage in simple sketches down. To use the AFSK examples, please also install these libraries:
- https://github.com/EnhancedRadioDevices/DDS
- https://github.com/EnhancedRadioDevices/HamShield_KISS
https://github.com/EnhancedRadioDevices/HamShield/wiki

89
SimpleFIFO.h Normal file
View File

@ -0,0 +1,89 @@
#ifndef SimpleFIFO_h
#define SimpleFIFO_h
/*
||
|| @file SimpleFIFO.h
|| @version 1.2
|| @author Alexander Brevig
|| @contact alexanderbrevig@gmail.com
||
|| @description
|| | A simple FIFO class, mostly for primitive types but can be used with classes if assignment to int is allowed
|| | This FIFO is not dynamic, so be sure to choose an appropriate size for it
|| #
||
|| @license
|| | Copyright (c) 2010 Alexander Brevig
|| | 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; version
|| | 2.1 of the License.
|| |
|| | 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
|| #
||
*/
template<typename T, int rawSize>
class SimpleFIFO {
public:
const int size; //speculative feature, in case it's needed
SimpleFIFO();
T dequeue(); //get next element
bool enqueue( T element ); //add an element
T peek() const; //get the next element without releasing it from the FIFO
void flush(); //[1.1] reset to default state
//how many elements are currently in the FIFO?
unsigned char count() { return numberOfElements; }
private:
#ifndef SimpleFIFO_NONVOLATILE
volatile unsigned char numberOfElements;
volatile unsigned char nextIn;
volatile unsigned char nextOut;
volatile T raw[rawSize];
#else
unsigned char numberOfElements;
unsigned char nextIn;
unsigned char nextOut;
T raw[rawSize];
#endif
};
template<typename T, int rawSize>
SimpleFIFO<T,rawSize>::SimpleFIFO() : size(rawSize) {
flush();
}
template<typename T, int rawSize>
bool SimpleFIFO<T,rawSize>::enqueue( T element ) {
if ( count() >= rawSize ) { return false; }
numberOfElements++;
nextIn %= size;
raw[nextIn] = element;
nextIn++; //advance to next index
return true;
}
template<typename T, int rawSize>
T SimpleFIFO<T,rawSize>::dequeue() {
numberOfElements--;
nextOut %= size;
return raw[ nextOut++];
}
template<typename T, int rawSize>
T SimpleFIFO<T,rawSize>::peek() const {
return raw[ nextOut % size];
}
template<typename T, int rawSize>
void SimpleFIFO<T,rawSize>::flush() {
nextIn = nextOut = numberOfElements = 0;
}
#endif

View File

@ -0,0 +1,132 @@
/* Serial glue to send messages over APRS
*
* To do: add message receive code
*
*/
#define DDS_REFCLK_DEFAULT 9600
#include <HamShield.h>
#include <avr/wdt.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
DDS dds;
String messagebuff = "";
String origin_call = "";
String destination_call = "";
String textmessage = "";
int msgptr = 0;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
// turn on pwr to the radio
digitalWrite(RESET_PIN, HIGH);
Serial.begin(115200);
radio.initialize();
radio.frequency(144390);
radio.setRfPower(0);
dds.start();
radio.afsk.start(&dds);
delay(100);
Serial.println("HELLO");
}
String temp[1] = "";
void loop() {
messagebuff = "KC7IBT,KC7IBT,:HAMSHIELD TEST";
prepMessage();
delay(10000);
}
void prepMessage() {
radio.setModeTransmit();
delay(500);
origin_call = messagebuff.substring(0,messagebuff.indexOf(',')); // get originating callsign
destination_call = messagebuff.substring(messagebuff.indexOf(',')+1,messagebuff.indexOf(',',messagebuff.indexOf(',')+1)); // get the destination call
textmessage = messagebuff.substring(messagebuff.indexOf(":")+1);
Serial.print("From: "); Serial.print(origin_call); Serial.print(" To: "); Serial.println(destination_call); Serial.println("Text: "); Serial.println(textmessage);
AFSK::Packet *packet = AFSK::PacketBuffer::makePacket(22 + 32);
packet->start();
packet->appendCallsign(origin_call.c_str(),0);
packet->appendCallsign(destination_call.c_str(),15,true);
packet->appendFCS(0x03);
packet->appendFCS(0xf0);
packet->print(textmessage);
packet->finish();
bool ret = radio.afsk.putTXPacket(packet);
if(radio.afsk.txReady()) {
Serial.println(F("txReady"));
radio.setModeTransmit();
//delay(100);
if(radio.afsk.txStart()) {
Serial.println(F("txStart"));
} else {
radio.setModeReceive();
}
}
// Wait 2 seconds before we send our beacon again.
Serial.println("tick");
// Wait up to 2.5 seconds to finish sending, and stop transmitter.
// TODO: This is hackery.
for(int i = 0; i < 500; i++) {
if(radio.afsk.encoder.isDone())
break;
delay(50);
}
Serial.println("Done sending");
delay(3000);
radio.setModeReceive();
}
ISR(TIMER2_OVF_vect) {
TIFR2 = _BV(TOV2);
static uint8_t tcnt = 0;
if(++tcnt == 8) {
digitalWrite(2, HIGH);
dds.clockTick();
digitalWrite(2, LOW);
tcnt = 0;
}
}
ISR(ADC_vect) {
static uint8_t tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
PORTD |= _BV(2); // Diagnostic pin (D2)
dds.clockTick();
if(++tcnt == 1) {
if(radio.afsk.encoder.isSending()) {
radio.afsk.timer();
}
tcnt = 0;
}
PORTD &= ~(_BV(2)); // Pin D2 off again
}

View File

@ -0,0 +1,139 @@
/* Serial glue to send messages over APRS
*
* To do: add message receive code
*
*/
#define DDS_REFCLK_DEFAULT 9600
#include <HamShield.h>
#include <avr/wdt.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
DDS dds;
String messagebuff = "";
String origin_call = "";
String destination_call = "";
String textmessage = "";
int msgptr = 0;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
// turn on the radio
digitalWrite(RESET_PIN, HIGH);
Serial.begin(115200);
radio.initialize();
radio.frequency(145570);
radio.setRfPower(0);
dds.start();
radio.afsk.start(&dds);
delay(100);
Serial.println("HELLO");
}
String temp[1] = "";
void loop() {
if(Serial.available()) {
char temp = (char)Serial.read();
if(temp == '`') {
prepMessage(); msgptr = 0; Serial.print("!!"); }
else {
messagebuff += temp;
msgptr++;
}
}
if(msgptr > 254) { messagebuff = ""; Serial.print("X!"); }
}
void prepMessage() {
radio.setModeTransmit();
delay(500);
origin_call = messagebuff.substring(0,messagebuff.indexOf(',')); // get originating callsign
destination_call = messagebuff.substring(messagebuff.indexOf(',')+1,
messagebuff.indexOf(',',messagebuff.indexOf(',')+1)); // get the destination call
textmessage = messagebuff.substring(messagebuff.indexOf(":"));
AFSK::Packet *packet = AFSK::PacketBuffer::makePacket(22 + 32);
packet->start();
packet->appendCallsign(origin_call.c_str(),0);
packet->appendCallsign(destination_call.c_str(),15,true);
packet->appendFCS(0x03);
packet->appendFCS(0xf0);
packet->print(textmessage);
packet->finish();
textmessage = "";
bool ret = radio.afsk.putTXPacket(packet);
if(radio.afsk.txReady()) {
Serial.println(F("txReady"));
//radio.setModeTransmit();
//delay(100);
if(radio.afsk.txStart()) {
Serial.println(F("txStart"));
} else {
radio.setModeReceive();
}
}
// Wait 2 seconds before we send our beacon again.
Serial.println("tick");
// Wait up to 2.5 seconds to finish sending, and stop transmitter.
// TODO: This is hackery.
for(int i = 0; i < 500; i++) {
if(radio.afsk.encoder.isDone())
break;
delay(50);
}
Serial.println("Done sending");
delay(3000);
radio.setModeReceive();
}
// TODO: d2 is now our switch, so don't write to that
ISR(TIMER2_OVF_vect) {
TIFR2 = _BV(TOV2);
static uint8_t tcnt = 0;
if(++tcnt == 8) {
//digitalWrite(2, HIGH);
dds.clockTick();
//digitalWrite(2, LOW);
tcnt = 0;
}
}
ISR(ADC_vect) {
static uint8_t tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
//PORTD |= _BV(2); // Diagnostic pin (D2)
dds.clockTick();
if(++tcnt == 1) {
if(radio.afsk.encoder.isSending()) {
radio.afsk.timer();
}
tcnt = 0;
}
//PORTD &= ~(_BV(2)); // Pin D2 off again
}

View File

@ -0,0 +1,105 @@
#include <HamShield.h>
HamShield radio;
DDS dds;
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
#define DON(p) PORTD |= _BV((p))
#define DOFF(p) PORTD &= ~(_BV((p)))
void setup() {
Serial.begin(9600);
pinMode(4, OUTPUT);
pinMode(5, OUTPUT);
pinMode(6, OUTPUT);
pinMode(7, OUTPUT);
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
// turn on pwr to the radio
digitalWrite(RESET_PIN, HIGH);
Serial.println(F("Radio test connection"));
Serial.println(radio.testConnection(), DEC);
Serial.println(F("Initialize"));
delay(100);
radio.initialize();
Serial.println(F("Frequency"));
delay(100);
radio.frequency(145010);
//radio.setRfPower(0);
delay(100);
dds.start();
delay(100);
radio.afsk.start(&dds);
delay(100);
dds.setFrequency(0);
dds.on();
dds.setAmplitude(255);
I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x44, 0b0000011111111111);
//I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x53, 0x0);
//I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x32, 0xffff);
}
void loop() {
DON(6);
AFSK::Packet *packet = AFSK::PacketBuffer::makePacket(22 + 32);
packet->start();
packet->appendCallsign("VE6SLP",0);
packet->appendCallsign("VA6GA",15,true);
packet->appendFCS(0x03);
packet->appendFCS(0xf0);
packet->print(F("Hello "));
packet->print(millis());
packet->println(F("\r\nThis is a test of the HamShield Kickstarter prototype. de VE6SLP"));
packet->finish();
bool ret = radio.afsk.putTXPacket(packet);
if(radio.afsk.txReady()) {
Serial.println(F("txReady"));
radio.setModeTransmit();
if(radio.afsk.txStart()) {
Serial.println(F("txStart"));
} else {
Serial.println(F("Tx Start failure"));
radio.setModeReceive();
}
}
// Wait 2 seconds before we send our beacon again.
Serial.println("tick");
// Wait up to 2.5 seconds to finish sending, and stop transmitter.
// TODO: This is hackery.
DOFF(6);
for(int i = 0; i < 500; i++) {
if(radio.afsk.encoder.isDone())
break;
delay(50);
Serial.println("Not done");
}
Serial.println("Done sending");
delay(100);
radio.setModeReceive();
delay(2000);
}
ISR(ADC_vect) {
TIFR1 = _BV(ICF1); // Clear the timer flag
DON(4);
dds.clockTick();
DON(5);
radio.afsk.timer();
DOFF(5);
DOFF(4);
}

View File

@ -1,165 +0,0 @@
/* Hamshield
* Example: AFSK Serial Messenger
* Serial glue to send messages over APRS. You will need a
* seperate AFSK receiver to test the output of this example.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. After uploading this program
* to your Arduino, open the Serial Monitor to monitor. Type
* a message under 254 characters into the bar at the top of
* the monitor. Click the "Send" button. Check for output on
* AFSK receiver.
*
* To send a message: connect to the Arduino over a Serial link.
* Send the following over the serial link:
* `from,to,:message
* example: * KG7OGM,KG7OGM,:Hi there`
*/
#include <HamShield.h>
#include <DDS.h>
#include <packet.h>
#include <avr/wdt.h>
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
DDS dds;
AFSK afsk;
String messagebuff = "";
String origin_call = "";
String destination_call = "";
String textmessage = "";
int msgptr = 0;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// prep the switch
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
// turn on the radio
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.begin(9600);
radio.initialize();
radio.frequency(144390); // default aprs frequency in North America
radio.setRfPower(0);
radio.setVolume1(0xFF);
radio.setVolume2(0xFF);
radio.setSQHiThresh(-100);
radio.setSQLoThresh(-100);
//radio.setSQOn();
radio.bypassPreDeEmph();
dds.start();
afsk.start(&dds);
delay(100);
radio.setModeReceive();
Serial.println("HELLO");
}
void loop() {
if(Serial.available()) {
char temp = (char)Serial.read();
if(temp == '`') {
//Serial.println(messagebuff);
prepMessage();
msgptr = 0;
messagebuff = "";
Serial.print("!!");
}
else {
messagebuff += temp;
msgptr++;
}
}
if(msgptr > 254) { messagebuff = ""; Serial.print("X!"); }
if(afsk.decoder.read() || afsk.rxPacketCount()) {
// A true return means something was put onto the packet FIFO
// If we actually have data packets in the buffer, process them all now
while(afsk.rxPacketCount()) {
AFSK::Packet *packet = afsk.getRXPacket();
Serial.print(F("Packet: "));
if(packet) {
packet->printPacket(&Serial);
AFSK::PacketBuffer::freePacket(packet);
}
}
}
}
void prepMessage() {
radio.setModeTransmit();
delay(1000);
origin_call = messagebuff.substring(0,messagebuff.indexOf(',')); // get originating callsign
destination_call = messagebuff.substring(messagebuff.indexOf(',')+1,messagebuff.indexOf(',',messagebuff.indexOf(',')+1)); // get the destination call
textmessage = messagebuff.substring(messagebuff.indexOf(":")+1);
// Serial.print("From: "); Serial.print(origin_call); Serial.print(" To: "); Serial.println(destination_call); Serial.println("Text: "); Serial.println(textmessage);
AFSK::Packet *packet = AFSK::PacketBuffer::makePacket(22 + 32);
packet->start();
packet->appendCallsign(origin_call.c_str(),0);
packet->appendCallsign(destination_call.c_str(),15,true);
packet->appendFCS(0x03);
packet->appendFCS(0xf0);
packet->print(textmessage);
packet->finish();
bool ret = afsk.putTXPacket(packet);
if(afsk.txReady()) {
Serial.println(F("txReady"));
radio.setModeTransmit();
//delay(100);
if(afsk.txStart()) {
Serial.println(F("txStart"));
} else {
radio.setModeReceive();
}
}
// Wait 2 seconds before we send our beacon again.
Serial.println("tick");
// Wait up to 2.5 seconds to finish sending, and stop transmitter.
// TODO: This is hackery.
for(int i = 0; i < 500; i++) {
if(afsk.encoder.isDone())
break;
delay(50);
}
Serial.println("Done sending");
radio.setModeReceive();
}
ISR(TIMER2_OVF_vect) {
TIFR2 = _BV(TOV2);
static uint8_t tcnt = 0;
if(++tcnt == 8) {
dds.clockTick();
tcnt = 0;
}
}
ISR(ADC_vect) {
static uint8_t tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
dds.clockTick();
if(++tcnt == 1) {
afsk.timer();
tcnt = 0;
}
}

View File

View File

View File

@ -0,0 +1,13 @@
chrome.app.runtime.onLaunched.addListener(function() {
chrome.app.window.create("window.html", {
"bounds": {
"width": 685,
"height": 800
}
});
});
$(function() {
$( "#tabs" ).tabs();
});

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

9789
examples/APRSMessenger/jquery-1.10.2.js vendored Normal file

File diff suppressed because it is too large Load Diff

1225
examples/APRSMessenger/jquery-ui.css vendored Normal file

File diff suppressed because it is too large Load Diff

16617
examples/APRSMessenger/jquery-ui.js vendored Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,10 @@
{
"name": "HamShield",
"description": "HamShield",
"version": "1.0.0",
"app": {
"background": {
"scripts": ["background.js"]
}
}
}

View File

@ -0,0 +1 @@
chromeApp

View File

@ -0,0 +1,48 @@
body{
display: inline-block;
}
.btn {
background: #adadad;
background-image: -webkit-linear-gradient(top, #adadad, #3d3d3d);
background-image: -moz-linear-gradient(top, #adadad, #3d3d3d);
background-image: -ms-linear-gradient(top, #adadad, #3d3d3d);
background-image: -o-linear-gradient(top, #adadad, #3d3d3d);
background-image: linear-gradient(to bottom, #adadad, #3d3d3d);
-webkit-border-radius: 0;
-moz-border-radius: 0;
border-radius: 0px;
font-family: Arial;
color: #ffffff;
font-size: 20px;
padding: 10px 20px 10px 20px;
text-decoration: none;
float: left;
text-align:center;
}
.btn:hover {
background: #3d3d3d;
text-decoration: none;
}
.lcd {
-webkit-border-radius: 0;
-moz-border-radius: 0;
border-radius: 0px;
font-family: Courier New;
color: #00ff00;
font-size: 50px;
background: #000000;
padding: 10px 20px 10px 20px;
text-decoration: none;
width: 500px;
}
.lcd:hover {
text-decoration: none;
}
.bs1 { width: 50px; }
.bs2 { width: 100px; }
.bs3 { width: 200px; }

View File

@ -0,0 +1,61 @@
<!DOCTYPE html>
<html lang="en">
<head>
<link rel="stylesheet" type="text/css" href="styles.css">
<meta charset="utf-8">
<title>APRSMessenger</title>
<link rel="stylesheet" href="jquery-ui.css">
<script src="jquery-1.10.2.js"></script>
<script src="jquery-ui.js"></script>
</head>
<body>
<div class="lcd" style="width: 768px">
144.390 MHz | APRS | <img src="bars-3.png" style="height: 32px; width: 32px;">
</div>
<div class="lcd" style="width: 768px; font-size: 15px;">
2M | BW: 25KHz | TX CTCSS: OFF | RX CTCSS: OFF | Filter: OFF | Presence: Available
</div>
<div class="btn" style="width: 75px">
Tune
</div>
<div class="btn">
Presence
</div>
<div class="btn">
GPS
</div>
<div class="btn">
SSTV
</div>
<div class="btn">
WX
</div>
<div class="btn">
MSG
</div>
<div class="btn">
SQ-
</div>
<div class="btn">
SQ+
</div>
<div class="btn">
VOL
</div>
<br/><br/>
<div id="tabs">
<ul>
<li><a href="#tabs-1">Console</a></li>
<li><a href="#tabs-2">KG7OGM</a></li>
<li><a href="#tabs-3">KC7IBT</a></li>
</ul>
</div>
<div id="tabs-1">
Debug messages
</div>
<div id="tabs-2">
</div>
<div id="tabs-3">
</div>
</body>
</html>

View File

@ -0,0 +1,77 @@
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
DDS dds;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
// turn on radio
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
Serial.println(F("Radio test connection"));
Serial.println(radio.testConnection(), DEC);
Serial.println(F("Initialize"));
delay(100);
radio.initialize();
radio.frequency(145010);
radio.setSQOff();
I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x44, 0b11111111);
Serial.println(F("Frequency"));
delay(100);
Serial.print(F("Squelch(H/L): "));
Serial.print(radio.getSQHiThresh());
Serial.print(F(" / "));
Serial.println(radio.getSQLoThresh());
radio.setModeReceive();
Serial.print(F("RX? "));
Serial.println(radio.getRX());
Serial.println(F("DDS Start"));
delay(100);
dds.start();
Serial.println(F("AFSK start"));
delay(100);
radio.afsk.start(&dds);
Serial.println(F("Starting..."));
delay(100);
dds.setAmplitude(255);
}
uint32_t last = 0;
void loop() {
if(radio.afsk.decoder.read() || radio.afsk.rxPacketCount()) {
// A true return means something was put onto the packet FIFO
// If we actually have data packets in the buffer, process them all now
while(radio.afsk.rxPacketCount()) {
AFSK::Packet *packet = radio.afsk.getRXPacket();
Serial.print(F("Packet: "));
if(packet) {
packet->printPacket(&Serial);
AFSK::PacketBuffer::freePacket(packet);
}
}
}
}
//TODO: d2 is the switch input, so remove this
ISR(ADC_vect) {
static uint8_t tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
//PORTD |= _BV(2); // Diagnostic pin (D2)
//dds.clockTick();
radio.afsk.timer();
//PORTD &= ~(_BV(2)); // Pin D2 off again
}

View File

@ -1,182 +0,0 @@
/* Hamshield
* Example: SerialController
* This application is used in conjunction with a computer to provide full serial control of HamShield.
*/
#include <HamShield.h>
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
uint8_t freq_buffer[32];
uint8_t pl_tx_buffer[32];
uint8_t pl_rx_buffer[32];
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.begin(9600);
Serial.println("If the sketch freezes at radio status, there is something wrong with power or the shield");
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
Serial.println("Setting radio to its defaults..");
radio.initialize();
radio.setRfPower(0);
radio.frequency(432100); // 70cm calling frequency
radio.setModeReceive();
}
void loop() {
if(Serial.available()) {
uint8_t buf = Serial.read();
Serial.write(buf);
switch (buf) {
case 'X': // absorb reset command because we are already reset
break;
case 'F': // frequency configuration command
tune_freq(); break;
case 'P': // TX PL Tone configuration command
pl_tone_tx(); break;
case 'R': // RX PL Tone configuration command
pl_tone_rx(); break;
case 'T': // turn on transmitter command
tx_on(); break;
case 'O': // turn off transmitter command
tx_off(); break;
case 'A': // configure amplifier
amplifier(); break;
case 'D': // configure predeemph
predeemph(); break;
default:
break;
}
}
}
void tx_on() {
radio.setModeTransmit();
Serial.println("Transmitting");
}
void tx_off() {
radio.setModeReceive();
Serial.println("Transmit off");
}
void pl_tone_tx() {
Serial.println("TX PL tone");
memset(pl_tx_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
Serial.write(buf);
if(buf == 'X') { return; }
if(buf == '!') { pl_tx_buffer[ptr] = 0; program_pl_tx(); return; }
if(ptr == 31) { return; }
pl_tx_buffer[ptr] = buf; ptr++;
}
}
}
void program_pl_tx() {
Serial.print("programming TX PL to ");
for(int x = 0; x < 32; x++) {
Serial.write(pl_tx_buffer[x]);
}
long pl_tx = atof(pl_tx_buffer);
Serial.print(" Which is FLOAT of ");
Serial.println(pl_tx,DEC);
radio.setCtcss(pl_tx);
}
void pl_tone_rx() {
Serial.println("RX PL tone");
memset(pl_rx_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
Serial.write(buf);
if(buf == 'X') { return; }
if(buf == '!') { pl_rx_buffer[ptr] = 0; program_pl_rx(); return; }
if(ptr == 31) { return; }
pl_rx_buffer[ptr] = buf; ptr++;
}
}
}
void program_pl_rx() {
Serial.print("programming RX PL to ");
for(int x = 0; x < 32; x++) {
Serial.write(pl_rx_buffer[x]);
}
long pl_rx = atof(pl_rx_buffer);
Serial.print(" Which is FLOAT of ");
Serial.println(pl_rx,DEC);
radio.setCtcss(pl_rx);
}
void tune_freq() {
Serial.println("program frequency mode");
memset(freq_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
Serial.write(buf);
if(buf == 'X') { return; }
if(buf == '!') { freq_buffer[ptr] = 0; program_frequency(); return; }
if(buf != '.') { freq_buffer[ptr] = buf; ptr++; }
if(ptr == 31) { return; }
}
}
}
void program_frequency() {
Serial.print("programming frequency to ");
for(int x = 0; x < 32; x++) {
Serial.write(freq_buffer[x]);
}
long freq = atol(freq_buffer);
Serial.print(" Which is LONG of ");
Serial.println(freq,DEC);
radio.frequency(freq);
}
void amplifier() {
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
Serial.write(buf);
if(buf == 'X') { return; }
if(buf != '!') { radio.setRfPower(buf); return; }
if(buf == '!') { return; }
}
}
}
void predeemph() { }

View File

@ -1,183 +0,0 @@
/* Hamshield
* Example: CTCSS
* This is a simple example to demonstrate HamShield receive
* and transmit functionality using CTCSS. The HamShield will
* have audio output muted until it receives the correct
* sub-audible tone. It does this by polling a tone detection
* flag on the HamShield, but it's also possible to do this
* using interrupts if you connect GPIO0 from the HamShield
* to your Arduino (code for that not provided).
*
* Setup:
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Plug a pair of headphones into
* the HamShield. Connect the Arduino to wall power and then
* to your computer via USB. Set the CTCSS tone that you
* want to use in the setup() function below.
* After uploading this program to your Arduino, open the
* Serial Monitor. Press the button on the HamShield to begin
* setup. The sketch then works exactly like the HandyTalkie
* example, with the exception that only valid CTCSS coded
* receptions are put out to the headset.
*/
#include <HamShield.h>
// create object for radio
HamShield radio;
#define LED_PIN 13
#define RSSI_REPORT_RATE_MS 5000
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
bool currently_tx;
uint32_t freq;
float ctcss_tone;
bool muted;
unsigned long rssi_timeout;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW);
// initialize serial communication
Serial.begin(9600);
Serial.println("press the switch to begin...");
while (digitalRead(SWITCH_PIN));
// let the AU ot of reset
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.println("beginning radio setup");
// verify connection
Serial.println("Testing device connections...");
Serial.println(radio.testConnection() ? "radio connection successful" : "radio connection failed");
// initialize device
Serial.println("Initializing radio device...");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration");
// set frequency
Serial.println("changing frequency");
freq = 432100; // 70cm calling frequency
radio.frequency(freq);
// set to receive
radio.setModeReceive();
currently_tx = false;
Serial.print("config register is: ");
Serial.println(radio.readCtlReg());
Serial.println(radio.readRSSI());
// set up squelch
radio.setSQLoThresh(-80);
radio.setSQHiThresh(-70);
radio.setSQOn();
radio.setRfPower(0);
// CTCSS Setup code
ctcss_tone = 131.8;
radio.setCtcss(ctcss_tone);
radio.enableCtcss();
Serial.print("ctcss tone: ");
Serial.println(radio.getCtcssFreqHz());
// mute audio until we get a CTCSS tone
radio.setMute();
muted = true;
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
rssi_timeout = 0;
}
void loop() {
// handle CTCSS tone detection
if (!currently_tx) {
// check for CTCSS tone
if (radio.getCtcssToneDetected()) {
if (muted) {
muted = false;
radio.setUnmute();
Serial.println("tone");
}
} else {
if (!muted) {
muted = true;
radio.setMute();
Serial.println("no tone");
}
}
}
// handle manual transmit
if (!digitalRead(SWITCH_PIN))
{
if (!currently_tx)
{
currently_tx = true;
// set to transmit
radio.setModeTransmit();
Serial.println("Tx");
radio.setUnmute(); // can't mute during transmit
muted = false;
}
} else if (currently_tx) {
radio.setModeReceive();
currently_tx = false;
Serial.println("Rx");
radio.setMute(); // default to mute during rx
muted = true;
}
// handle serial commands
if (Serial.available()) {
if (Serial.peek() == 'r') {
Serial.read();
digitalWrite(RESET_PIN, LOW);
delay(1000);
digitalWrite(RESET_PIN, HIGH);
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
} else {
Serial.setTimeout(40);
freq = Serial.parseInt();
while (Serial.available()) Serial.read();
radio.frequency(freq);
Serial.print("set frequency: ");
Serial.println(freq);
}
}
// periodically read RSSI and print to screen
if (!currently_tx && (millis() - rssi_timeout) > RSSI_REPORT_RATE_MS)
{
Serial.println(radio.readRSSI());
rssi_timeout = millis();
}
}

View File

@ -0,0 +1,8 @@
chrome.app.runtime.onLaunched.addListener(function() {
chrome.app.window.create("window.html", {
"bounds": {
"width": 685,
"height": 263
}
});
});

View File

@ -0,0 +1,10 @@
{
"name": "HamShield",
"description": "HamShield",
"version": "1.0.0",
"app": {
"background": {
"scripts": ["background.js"]
}
}
}

View File

@ -0,0 +1 @@
chromeApp

View File

@ -0,0 +1,48 @@
body{
display: inline-block;
}
.btn {
background: #adadad;
background-image: -webkit-linear-gradient(top, #adadad, #3d3d3d);
background-image: -moz-linear-gradient(top, #adadad, #3d3d3d);
background-image: -ms-linear-gradient(top, #adadad, #3d3d3d);
background-image: -o-linear-gradient(top, #adadad, #3d3d3d);
background-image: linear-gradient(to bottom, #adadad, #3d3d3d);
-webkit-border-radius: 0;
-moz-border-radius: 0;
border-radius: 0px;
font-family: Arial;
color: #ffffff;
font-size: 20px;
padding: 10px 20px 10px 20px;
text-decoration: none;
float: left;
text-align:center;
}
.btn:hover {
background: #3d3d3d;
text-decoration: none;
}
.lcd {
-webkit-border-radius: 0;
-moz-border-radius: 0;
border-radius: 0px;
font-family: Courier New;
color: #00ff00;
font-size: 50px;
background: #000000;
padding: 10px 20px 10px 20px;
text-decoration: none;
width: 500px;
}
.lcd:hover {
text-decoration: none;
}
.bs1 { width: 50px; }
.bs2 { width: 100px; }
.bs3 { width: 200px; }

View File

@ -0,0 +1,67 @@
<!DOCTYPE html>
<html>
<head>
<link rel="stylesheet" type="text/css" href="styles.css">
</head>
<body>
<div class="lcd" style="width: 623px">
220.000 MHz
</div>
<div class="lcd" style="width: 623px; font-size: 15px;">
1.25M | BW 12.5KHz | TX CTCSS: 103.5 | RX CTCSS: 109.4 | Filter OFF
</div>
<div class="btn" style="width: 75px">
BW
</div>
<div class="btn">
Band
</div>
<div class="btn">
+
</div>
<div class="btn">
-
</div>
<div class="btn">
&lt;&lt;
</div>
<div class="btn">
&gt;&gt;
</div>
<div class="btn">
SQ-
</div>
<div class="btn">
SQ+
</div>
<div class="btn">
VOL
</div>
<br/>
<div class="btn">
CTCSS
</div>
<div class="btn">
CDCSS
</div>
<div class="btn">
Vox
</div>
<div class="btn">
Filter
</div>
<div class="btn">
Offset
</div>
<div class="btn">
Directory
</div>
<div class="btn">
WX
</div>
<br/>
<div class="btn" style="width: 622px">
Transmit
</div>
</body>
</html>

View File

@ -0,0 +1,269 @@
#define DDS_REFCLK_DEFAULT 38400
#define DDS_REFCLK_OFFSET 0
#define DDS_DEBUG_SERIAL
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
DDS dds;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
// turn on radio
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
radio.initialize();
radio.setRfPower(0);
radio.setFrequency(145050);
dds.start();
dds.setFrequency(1200);
dds.on();
radio.bypassPreDeEmph();
}
enum Sets {
SET_REF,
SET_TONE,
SET_AMPLITUDE,
SET_ADC_HALF,
SET_OFFSET
} setting = SET_TONE;
char freqBuffer[8];
char *freqBufferPtr = freqBuffer;
uint16_t lastFreq = 1200;
volatile uint16_t recordedPulseLength;
volatile bool recordedPulse = false;
volatile bool listening = false;
volatile uint8_t maxADC = 0, minADC = 255, adcHalf = 40;
void loop() {
static uint16_t samples = 0;
static uint16_t pulse;
static uint32_t lastOutput = 0;
static float pulseFloat = 0.0;
if(recordedPulse) {
uint32_t pulseAveraging;
uint16_t tmpPulse;
cli();
recordedPulse = false;
tmpPulse = recordedPulseLength;
sei();
if(samples++ == 0) {
pulse = tmpPulse;
//pulseFloat = tmpPulse;
} else {
pulseAveraging = (pulse + tmpPulse) >> 1;
pulse = pulseAveraging;
pulseFloat = pulseFloat + 0.01*((float)pulse-pulseFloat);
}
if((lastOutput + 1000) < millis()) {
Serial.print(F("Pulse: "));
Serial.println(pulse);
Serial.print(F("Last: "));
Serial.println(tmpPulse);
Serial.print(F("Samples: "));
Serial.println(samples);
Serial.print(F("ADC M/M: "));
Serial.print(minADC); minADC = 255;
Serial.print(F(" / "));
Serial.println(maxADC); maxADC = 0;
Serial.print(F("Freq: "));
// F = 1/(pulse*(1/ref))
// F = ref/pulse
Serial.print((float)((float)dds.getReferenceClock()+(float)dds.getReferenceOffset())/(float)pulse);
Serial.print(F(" / "));
Serial.print((float)((float)dds.getReferenceClock()+(float)dds.getReferenceOffset())/pulseFloat);
Serial.print(F(" / "));
Serial.println(pulseFloat);
Serial.print(F("Freq2: "));
// F = 1/(pulse*(1/ref))
// F = ref/pulse
Serial.print((float)dds.getReferenceClock()/(float)pulse);
Serial.print(F(" / "));
Serial.println((float)dds.getReferenceClock()/pulseFloat);
samples = 0;
lastOutput = millis();
}
}
while(Serial.available()) {
char c = Serial.read();
Serial.print(c);
switch(c) {
case 'h':
Serial.println(F("Commands:"));
Serial.println(F("RefClk: u = +10, U = +100, r XXXX = XXXX"));
Serial.println(F(" d = -10, D = -100"));
Serial.println(F("Offset: s XXX = Set refclk offset"));
Serial.println(F("Radio: T = transmit, R = receive"));
Serial.println(F("Tone: t XXXX = XXXX Hz"));
Serial.println(F("Amp.: a XXX = XXX out of 255"));
Serial.println(F("DDS: o = On, O = Off"));
Serial.println(F("Input: l = Determine received frequency, L = stop"));
Serial.println(F("ADC: m XXX = Set ADC midpoint (zero crossing level)"));
Serial.println(F("ie. a 31 = 32/255 amplitude, r38400 sets 38400Hz refclk"));
Serial.println("> ");
break;
case 'u':
dds.setReferenceClock(dds.getReferenceClock()+10);
dds.setFrequency(lastFreq);
dds.start();
Serial.println(F("RefClk + 10 = "));
Serial.println(dds.getReferenceClock());
Serial.println("> ");
break;
case 'U':
dds.setReferenceClock(dds.getReferenceClock()+100);
dds.setFrequency(lastFreq);
dds.start();
Serial.println(F("RefClk + 100 = "));
Serial.println(dds.getReferenceClock());
Serial.println("> ");
break;
case 'd':
dds.setReferenceClock(dds.getReferenceClock()-10);
dds.setFrequency(lastFreq);
dds.start();
Serial.println(F("RefClk - 10 = "));
Serial.println(dds.getReferenceClock());
Serial.println("> ");
break;
case 'D':
dds.setReferenceClock(dds.getReferenceClock()-100);
dds.setFrequency(lastFreq);
dds.start();
Serial.println(F("RefClk - 100 = "));
Serial.println(dds.getReferenceClock());
Serial.println("> ");
break;
case 'l':
Serial.println(F("Start frequency listening, DDS off"));
dds.off();
listening = true;
lastOutput = millis();
Serial.println("> ");
break;
case 'L':
Serial.println(F("Stop frequency listening, DDS on"));
listening = false;
samples = 0;
dds.on();
Serial.println("> ");
break;
case 'T':
Serial.println(F("Radio transmit"));
radio.setModeTransmit();
Serial.println("> ");
break;
case 'R':
Serial.println(F("Radio receive"));
radio.setModeReceive();
Serial.println("> ");
break;
case 'r':
setting = SET_REF;
break;
case 't':
setting = SET_TONE;
break;
case 'a':
setting = SET_AMPLITUDE;
break;
case 'm':
setting = SET_ADC_HALF;
break;
case 's':
setting = SET_OFFSET;
break;
case 'o':
dds.on();
Serial.println("> ");
break;
case 'O':
dds.off();
Serial.println("> ");
break;
default:
if(c == '-' || (c >= '0' && c <= '9')) {
*freqBufferPtr = c;
freqBufferPtr++;
}
if((c == '\n' || c == '\r') && freqBufferPtr != freqBuffer) {
*freqBufferPtr = '\0';
freqBufferPtr = freqBuffer;
uint16_t freq = atoi(freqBuffer);
if(setting == SET_REF) {
dds.setReferenceClock(freq);
dds.setFrequency(lastFreq);
dds.start();
Serial.print(F("New Reference Clock: "));
Serial.println(dds.getReferenceClock());
} else if(setting == SET_TONE) {
dds.setFrequency(freq);
lastFreq = freq;
Serial.print(F("New Tone: "));
Serial.println(freq);
} else if(setting == SET_AMPLITUDE) {
dds.setAmplitude((uint8_t)(freq&0xFF));
Serial.print(F("New Amplitude: "));
Serial.println((uint8_t)(freq&0xFF));
} else if(setting == SET_ADC_HALF) {
adcHalf = freq&0xFF;
Serial.print(F("ADC midpoint set to "));
Serial.println((uint8_t)(freq&0xFF));
} else if(setting == SET_OFFSET) {
dds.setReferenceOffset((int16_t)atoi(freqBuffer));
dds.setFrequency(lastFreq);
Serial.print(F("Refclk offset: "));
Serial.println(dds.getReferenceOffset());
}
Serial.println("> ");
}
break;
}
}
}
ISR(ADC_vect) {
static uint16_t pulseLength = 0;
static uint8_t lastADC = 127;
cli();
TIFR1 = _BV(ICF1);
//PORTD |= _BV(2);
dds.clockTick();
sei();
if(listening) {
pulseLength++;
if(ADCH >= adcHalf && lastADC < adcHalf) {
// Zero crossing, upward
recordedPulseLength = pulseLength;
recordedPulse = true;
pulseLength = 0;
}
if(minADC > ADCH) {
minADC = ADCH;
}
if(maxADC < ADCH) {
maxADC = ADCH;
}
lastADC = ADCH;
}
//PORTD &= ~_BV(2);
}

View File

@ -1,50 +1,32 @@
/* Hamshield
* Example: DDS
* This is a simple example to show how to transmit arbitrary
* tones. In this case, the sketh alternates between 1200Hz
* and 2200Hz at 1s intervals.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. Upload this program
* to your Arduino. To test, set a HandyTalkie to 438MHz. You
* should hear two alternating tones.
*/
#define DDS_REFCLK_DEFAULT 9600
#include <HamShield.h>
#include <DDS.h>
#define MIC_PIN 3
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
#define DDS_USE_ONLY_TIMER2 true
#define TIMER2_PHASE_ADVANCE 24
HamShield radio;
DDS dds;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
// turn on radio
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
radio.initialize();
radio.setRfPower(0);
radio.frequency(438000);
radio.setFrequency(145060);
radio.setModeTransmit();
dds.start();
dds.startPhaseAccumulator(DDS_USE_ONLY_TIMER2);
dds.playWait(600, 3000);
dds.on();
//dds.setAmplitude(31);
@ -57,22 +39,19 @@ void loop() {
delay(1000);
}
#if DDS_USE_ONLY_TIMER2
#ifdef DDS_USE_ONLY_TIMER2
ISR(TIMER2_OVF_vect) {
static unsigned char tcnt = 0;
if(++tcnt == TIMER2_PHASE_ADVANCE) {
tcnt = 0;
dds.clockTick();
}
dds.clockTick();
}
#else // Use the ADC timer instead
ISR(ADC_vect) {
static unsigned char tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
if(++tcnt == 4) {
//digitalWrite(2, HIGH);
tcnt = 0;
}
dds.clockTick();
//digitalWrite(2, LOW);
}
#endif

View File

@ -1,153 +0,0 @@
/* Hamshield
* Example: DTMF
* This is a simple example to demonstrate how to use DTMF.
*
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack.
* Connect the Arduino to wall power and then to your computer
* via USB. After uploading this program to your Arduino, open
* the Serial Monitor. Press the switch on the HamShield to
* begin setup. After setup is complete, type in a DTMF value
* (0-9, A, B, C, D, *, #) and hit enter. The corresponding
* DTMF tones will be transmitted. The sketch will also print
* any received DTMF tones to the screen.
**/
#include <HamShield.h>
// create object for radio
HamShield radio;
#define LED_PIN 13
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
uint32_t freq;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW);
// initialize serial communication
Serial.begin(9600);
Serial.println("press the switch to begin...");
while (digitalRead(SWITCH_PIN));
// now we let the AU ot of reset
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.println("beginning radio setup");
// verify connection
Serial.println("Testing device connections...");
Serial.println(radio.testConnection() ? "HamShield connection successful" : "HamShield connection failed");
// initialize device
radio.initialize();
Serial.println("setting default Radio configuration");
Serial.println("setting squelch");
radio.setSQHiThresh(-10);
radio.setSQLoThresh(-30);
Serial.print("sq hi: ");
Serial.println(radio.getSQHiThresh());
Serial.print("sq lo: ");
Serial.println(radio.getSQLoThresh());
radio.setSQOn();
//radio.setSQOff();
Serial.println("setting frequency to: ");
freq = 432100; // 70cm calling frequency
radio.frequency(freq);
Serial.print(radio.getFrequency());
Serial.println("kHz");
// set RX volume to minimum to reduce false positives on DTMF rx
radio.setVolume1(6);
radio.setVolume2(0);
// set to receive
radio.setModeReceive();
radio.setRfPower(0);
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
// set up DTMF
radio.enableDTMFReceive();
/* DTMF timing settings are optional.
* These times are set to default values when the device is started.
* You may want to change them if you're DTMF receiver isn't detecting
* codes from the HamShield (or vice versa).
*/
radio.setDTMFDetectTime(24); // time to detect a DTMF code, units are 2.5ms
radio.setDTMFIdleTime(50); // time between transmitted DTMF codes, units are 2.5ms
radio.setDTMFTxTime(60); // duration of transmitted DTMF codes, units are 2.5ms
Serial.println("ready");
}
void loop() {
// look for tone
char m = radio.DTMFRxLoop();
if (m != 0) {
Serial.print(m);
}
// Is it time to send tone?
if (Serial.available()) {
// get first code
uint8_t code = radio.DTMFchar2code(Serial.read());
// start transmitting
radio.setDTMFCode(code); // set first
radio.setTxSourceTones();
radio.setModeTransmit();
delay(300); // wait for TX to come to full power
bool dtmf_to_tx = true;
while (dtmf_to_tx) {
// wait until ready
while (radio.getDTMFTxActive() != 1) {
// wait until we're ready for a new code
delay(10);
}
if (Serial.available()) {
code = radio.DTMFchar2code(Serial.read());
if (code == 255) code = 0xE; // throw a * in there so we don't break things with an invalid code
radio.setDTMFCode(code); // set first
} else {
dtmf_to_tx = false;
break;
}
while (radio.getDTMFTxActive() != 0) {
// wait until this code is done
delay(10);
}
}
// done with tone
radio.setModeReceive();
radio.setTxSourceMic();
}
}

View File

@ -1,41 +1,32 @@
/* Hamshield
* Example: Morse Code Beacon
*
* Test beacon will transmit and wait 30 seconds.
* Beacon will check to see if the channel is clear before it
* will transmit.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. After uploading
* this program to your Arduino, open the Serial Monitor to
* monitor the status of the beacon. To test, set a HandyTalkie
* to 438MHz. You should hear the message " CALLSIGN HAMSHIELD"
* in morse code.
/*
Morse Code Beacon
Test beacon will transmit and wait 30 seconds.
Beacon will check to see if the channel is clear before it will transmit.
*/
#define DDS_REFCLK_DEFAULT 9600
// Include the HamSheild
#include <HamShield.h>
#define MIC_PIN 3
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
// Create a new instance of our HamSheild class, called 'radio'
HamShield radio;
// Run our start up things here
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
// Set up the serial port at 9600 Baud
Serial.begin(9600);
@ -50,16 +41,9 @@ void setup() {
// Tell the HamShield to start up
radio.initialize();
// Set the transmit power level (0-8)
radio.setRfPower(0);
// Set the morse code characteristics
radio.setMorseFreq(600);
radio.setMorseDotMillis(100);
// Configure the HamShield
radio.frequency(432300); // 70cm beacon frequency
// Configure the HamShield to transmit and recieve on 446.000MHz
radio.frequency(145570);
Serial.println("Radio Configured.");
}
@ -76,17 +60,20 @@ void loop() {
radio.setModeTransmit();
// Send a message out in morse code
radio.morseOut(" CALLSIGN HAMSHIELD");
radio.morseOut("KC7IBT ARDUINO HAMSHIELD");
// We're done sending the message, set the radio back into recieve mode.
radio.setModeReceive();
Serial.println("Done.");
// Wait 30 seconds before we send our beacon again.
delay(1000);
} else {
// If we get here, the channel is busy. Let's also print out the RSSI.
Serial.print("The channel was busy. Waiting 10 seconds. RSSI: ");
Serial.println(radio.readRSSI());
}
// Wait 30 seconds before we send our beacon again.
delay(30000);
// Wait 10 seconds and check the channel again.
delay(10000);
}
}

View File

@ -0,0 +1,283 @@
// BlueHAM Proto01 Connection Guide
/**********************
**
** BlueHAM Proto01 <--> Arduino
** ADC_SCL A5
** ADC_DIO A4
** GND GND
** PWM_RF_CTL D9
**
** Setting Connections
** MODE -> GND
** SENB -> GND
** PDN -> 3.3V
** AVDD -> 5V (note this should be a beefy supply, could draw up to 4As)
**
**
**
** Pinout information for RadioPeripheral01 Prototype board
** GPIO0 -
** GPIO1 -
** GPIO2 - VHF_SEL
** GPIO3 - UHF_SEL
** GPIO4 - RX_EN
** GPIO5 - TX_EN
** GPIO6 -
** GPIO7 -
**************************/
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#include "Wire.h"
#include "HAMShield.h"
#include <Goertzel.h>
//typedef enum {
#define MAIN_S 0
#define RX_S 1
#define TX_S 2
#define FREQ_S 3
#define UHF_S 4
#define VHF_S 5
#define PWR_S 6
#define GPIO_S 7
//} menu_view;
int state;
/* goertzel routines */
int sensorPin = A0;
int led = 13;
const float TARGET_FREQUENCY = 2200;
const int N = 100;
const float THRESHOLD = 4000;
const float SAMPLING_FREQUENCY = 8900;
Goertzel goertzel = Goertzel(TARGET_FREQUENCY, N, SAMPLING_FREQUENCY);
// create object for RDA
HAMShield radio;
#define LED_PIN 13
bool blinkState = false;
void setup() {
// initialize serial communication
Serial.begin(115200);
Serial.println("beginning radio setup");
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// verify connection
Serial.println("Testing device connections...");
Serial.println(radio.testConnection() ? "RDA radio connection successful" : "RDA radio connection failed");
// initialize device
Serial.println("Initializing I2C devices...");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration");
// set frequency
Serial.println("changing frequency");
radio.setFrequency(446000); // in kHz
radio.setModeReceive();
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
state = MAIN_S;
print_menu();
}
void loop() {
goertzel.sample(sensorPin);
float magnitude = goertzel.detect();
if(magnitude>THRESHOLD) digitalWrite(led, HIGH); //if found, enable led
else digitalWrite(led, LOW);
while (Serial.available()) {
if (state == FREQ_S) {
char freq_khz[6];
int i = 0;
while(i < 6) {
if (Serial.available()) {
freq_khz[i] = Serial.read();
i++;
}
}
// interpret frequency
uint32_t freq = 0;
i = 0;
while (i < 6) {
uint32_t temp = freq_khz[i] - '0';
for (int k = 5-i; k > 0; k--) {
temp = temp * 10;
}
freq += temp;
i++;
}
Serial.print("setting frequency to: ");
Serial.println(freq);
radio.setFrequency(freq);
state = MAIN_S;
} else if (state == PWR_S) {
uint8_t pwr_raw[3];
int i = 0;
while(i < 3) {
if (Serial.available()) {
pwr_raw[i] = Serial.read();
i++;
}
}
// interpret power
uint8_t pwr = 0;
i = 0;
while (i < 3) {
uint8_t temp = pwr_raw[i] - '0';
for (int k = 2-i; k > 0; k--) {
temp = temp * 10;
}
pwr += temp;
i++;
}
Serial.print("Setting power to: ");
Serial.println(pwr);
radio.setRfPower(pwr);
state = MAIN_S;
} else if (state == GPIO_S) {
uint8_t gpio_raw[2];
int i = 0;
while(i < 2) {
if (Serial.available()) {
gpio_raw[i] = Serial.read();
i++;
}
}
uint16_t gpio_pin = gpio_raw[0] - 48; // '0';
uint16_t gpio_mode = gpio_raw[1] - 48;
radio.setGpioMode(gpio_pin, gpio_mode);
state = MAIN_S;
} else {
char action = Serial.read();
if (action == 'r') { // get current state
state = RX_S;
} else if (action == 't') {
state = TX_S;
} else if (action == 'f') {
state = FREQ_S;
} else if (action == 'u') {
state = UHF_S;
} else if (action == 'v') {
state = VHF_S;
} else if (action == '1') {
turn_on(state);
state = MAIN_S;
} else if (action == '0') {
turn_off(state);
state = MAIN_S;
} else if (action == 'p') {
state = PWR_S;
} else if (action == 'g') {
state = GPIO_S;
} else if (action == 's') {
int16_t rssi = radio.readRSSI();
Serial.print("rssi: ");
Serial.println(rssi);
} else if (action == 'i') {
int16_t vssi = radio.readVSSI();
Serial.print("vssi: ");
Serial.println(vssi);
}
Serial.println(action);
}
Serial.flush();
print_menu();
}
}
void turn_off(int dev) {
switch (dev) {
case RX_S:
radio.setRX(0);
break;
case TX_S:
radio.setTX(0);
break;
case UHF_S:
radio.setGpioMode(3, 3); // set GPIO3 high (uhf is active low)
break;
case VHF_S:
radio.setGpioMode(2, 3); // set GPIO2 high (vhf is active low)
break;
default:
break;
}
}
void turn_on(int dev) {
switch (dev) {
case RX_S:
radio.setRX(1);
break;
case TX_S:
radio.setTX(1);
break;
case UHF_S:
radio.setGpioMode(3, 2); // set GPIO3 low (uhf is active low)
break;
case VHF_S:
radio.setGpioMode(2, 2); // set GPIO2 low (uhf is active low)
break;
default:
break;
}
}
void print_menu() {
Serial.println("MENU");
switch (state) {
case MAIN_S:
Serial.println("select step: [r]x, [t]x, [f]req, [u]hf, [v]hf, [p]wr, [g]pio control, r[s]si, vss[i] ...");
break;
case RX_S:
Serial.println("enter 1 to turn on rx, 0 to turn off rx");
break;
case TX_S:
Serial.println("enter 1 to turn on tx, 0 to turn off tx");
break;
case FREQ_S:
Serial.println("enter frequency in kHz (ffffff)");
break;
case UHF_S:
Serial.println("enter 1 to turn on uhf, 0 to turn off uhf");
break;
case VHF_S:
Serial.println("enter 1 to turn on vhf, 0 to turn off vhf");
break;
case PWR_S:
Serial.println("enter power (raw) (ppp)");
break;
case GPIO_S:
Serial.println("enter GPIO pin and control (no spaces, eg pin 1 mode 3 is 13");
Serial.println("modes 0 - HiZ, 1 - FCN, 2 - Low, 3 - Hi");
break;
default:
state = MAIN_S;
break;
}
}

View File

@ -1,27 +1,14 @@
/* Hamshield
* Example: Fox Hunt
*
* Plays a one minute tone, then IDs at 10-13 minute intervals. Script
* will check to see if the channel is clear before it will transmit.
*
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. After uploading
* this program to your Arduino, open the Serial Monitor to
* monitor the status of the beacon. To test, set a HandyTalkie
* to 438MHz. You should hear a one-minute tone followed by
* a callsign every 10-13 minutes.
*/
/* Fox Hunt */
#include <HamShield.h>
#define MIC_PIN 3
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
// In milliseconds
#define TRANSMITLENGTH 60000
// In minutes
// transmit for 1 minute, every 10 minutes
#define TRANSMITLENGTH 1
#define INTERVAL 10
#define RANDOMCHANCE 3
@ -29,76 +16,34 @@ HamShield radio;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
// Set up the serial port at 9600 Baud
Serial.begin(9600);
// Send a quick serial string
Serial.println("HamShield FoxHunt Example Sketch");
// Query the HamShield for status information
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result, DEC);
// Tell the HamShield to start up
radio.initialize();
// Set the transmit power level (0-8)
radio.setRfPower(0);
// Set the morse code characteristics
radio.setMorseFreq(600);
radio.setMorseDotMillis(100);
// Configure the HamShield frequency
radio.frequency(432400);
Serial.println("Radio configured.");
radio.frequency(145510);
radio.setModeReceive();
}
void loop() {
// We'll wait up to 30 seconds for a clear channel, requiring that the channel is clear for 2 seconds before we transmit
if (radio.waitForChannel(30000,2000, -90)) {
// If we get here, the channel is clear. Let's print the RSSI to the serial port as well.
Serial.print("Signal is clear, RSSI: ");
Serial.println(radio.readRSSI());
// Set the HamShield to TX
Serial.print("Transmitting...");
radio.setModeTransmit();
// Generate a 600Hz tone for TRANSMITLENGTH time
tone(MIC_PIN, 600, TRANSMITLENGTH);
delay(TRANSMITLENGTH);
// Identify the transmitter
radio.morseOut(" CALLSIGN FOXHUNT");
// Set the HamShield back to RX
radio.setModeReceive();
Serial.println("Done.");
// Wait for INTERLVAL + some random minutes before transmitting again
waitMinute(INTERVAL + random(0,RANDOMCHANCE));
}
waitMinute(INTERVAL + random(0,RANDOMCHANCE)); // wait before transmitting, randomly up to 3 minutes later
if(radio.waitForChannel(30000,2000, -90)) { // wait for a clear channel, abort after 30 seconds, wait 2 seconds of dead air for breakers
radio.setModeTransmit(); // turn on transmit mode
tone(1000,11,TRANSMITLENGTH * 60 * 1000); // play a long solid tone
radio.morseOut("1ZZ9ZZ/B FOXHUNT"); // identify the fox hunt transmitter
radio.setModeReceive(); // turn off the transmit mode
}
}
// a function so we can wait by minutes
void waitMinute(unsigned long period) {
Serial.print("Waiting for ");
Serial.print(period, DEC);
Serial.println(" minutes.");
void waitMinute(int period) {
delay(period * 60 * 1000);
}

View File

@ -0,0 +1,69 @@
/* HamShield Functional Test */
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
Serial.println("If the sketch freezes at radio status, there is something wrong with power or the shield");
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
Serial.println("Setting radio to its defaults..");
radio.initialize();
}
void loop() {
radio.setModeReceive();
radio.setSQLoThresh(0);
radio.setSQOn();
radio.setVolume1(0xF);
radio.setVolume2(0xF);
delay(1000);
Serial.println("Changing frequency to 446.000 and waiting 10 seconds. You should hear static fading in.");
radio.frequency(446000);
for(int x = 0; x < 16; x++) { radio.setVolume1(x); delay(500); Serial.print(x); Serial.print(".."); }
for(int x = 0; x < 16; x++) { radio.setVolume2(x); delay(500); Serial.print(x); Serial.print(".."); }
radio.setVolume1(0xF);
radio.setVolume2(0xF);
delay(10000);
Serial.println("Changing frequency to 450.000 and waiting 10 seconds. You should hear static.");
radio.frequency(446000);
delay(10000);
Serial.println("Changing frequency to 220.000 and waiting 10 seconds. you should hear static.");
radio.frequency(220000);
delay(10000);
Serial.println("Changing frequency to 144.520 and waiting 10 seconds. you should hear static.");
radio.frequency(144520);
delay(10000);
Serial.println("Now lets scan for a weather radio station and listen for a while....");
radio.setWXChannel(radio.scanWXChannel());
Serial.println("If you hear weather radio, it means the scanWXChannel() and setWXChannel() and VHF works.");
Serial.println("We will sit here for 30 seconds because weather is important.");
delay(30000);
Serial.println("We will now tune to 446.000 and send morse code");
radio.frequency(446000);
radio.setModeTransmit();
radio.morseOut("HELLO PERSON");
radio.setModeReceive();
Serial.println("Now we are receiving on the call frequency. Starting over again.");
}

114
examples/Gauges/Gauges.ino Executable file
View File

@ -0,0 +1,114 @@
/*
Gauges
Simple gauges for the radio receiver.
*/
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
void clr() {
/* Serial.write(27);
Serial.print("[2J"); // cursor to home command */
Serial.write(27);
Serial.print("[H"); // cursor to home command
}
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
analogReference(DEFAULT);
Serial.begin(115200);
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
radio.initialize();
radio.setFrequency(446000);
radio.setModeReceive();
Serial.println("Entering gauges...");
tone(9,1000);
delay(2000);
}
int gauge;
int x = 0;
int y = 0;
int peak = 0;
int a = 0;
int mini = 0;
int vpeak = 0;
int txc = 0;
int mode = 0;
void loop() {
clr();
int16_t rssi = radio.readRSSI();
gauge = map(rssi,-123,-50,0,8);
Serial.print("[");
for(x = 0; x < gauge; x++) {
Serial.print(".");
}
Serial.print("|");
for(y = x; y < 8; y++) {
Serial.print(".");
}
Serial.print("] ");
Serial.print(rssi);
Serial.println(" ");
Serial.println("Signal \n");
// radio.setModeTransmit();
int16_t vssi = radio.readVSSI();
// radio.setModeReceive();
if(vssi > vpeak) { vpeak = vssi; }
gauge = map(vssi,-50,-150,0,8);
Serial.print("[");
for(x = 0; x < gauge; x++) {
Serial.print(".");
}
Serial.print("|");
for(y = x; y < 8; y++) {
Serial.print(".");
}
Serial.print("] ");
Serial.print(vpeak);
Serial.println(" ");
Serial.println("Audio In\n");
a = analogRead(0);
if(a > peak) { peak = a; }
if(a < mini) { mini = a; }
gauge = map(a,400,1023,0,8);
Serial.print("[");
for(x = 0; x < gauge; x++) {
Serial.print(".");
}
Serial.print("|");
for(y = x; y < 8; y++) {
Serial.print(".");
}
Serial.print("] ");
Serial.print(a,DEC);
Serial.print(" ("); Serial.print(peak,DEC); Serial.println(") ");
Serial.println("Audio RX ADC Peak\n");
}

46
examples/HAMBot/HAMBot.ino Executable file
View File

@ -0,0 +1,46 @@
/* Simple DTMF controlled HAM Radio Robot */
#include <ArduinoRobot.h> // include the robot library
#include <HamShield.h>
#include <SPI.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Robot.begin();
radio.initialize();
radio.frequency(145510);
}
void loop() {
if(radio.waitForDTMF()) { // wait for a received DTMF tone
uint8_t command = radio.getLastDTMFDigit(); // get the last DTMF tone sent
if(command == '4') { Robot.turn(-90); } // turn robot left
if(command == '6') { Robot.turn(90); } // turn robot right
if(command == '2') { Robot.motorsWrite(-255,-255); delay(500); Robot.motorsWrite(255, 255); } // move robot forward
if(command == '5') { // tell robot to send morse code identity
if(radio.waitForChannel()) { // wait for the user to release the transmit button
radio.setModeTransmit(); // turn on transmit mode
radio.morseOut("1ZZ9ZZ I AM HAMRADIO ROBOT"); // send morse code
radio.setModeReceive(); // go back to receive mode on radio
}
}
}
}

View File

@ -1,32 +1,15 @@
/* Hamshield
* Example: HandyTalkie
* This is a simple example to demonstrate HamShield receive
* and transmit functionality.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Plug a pair of headphones into
* the HamShield. Connect the Arduino to wall power and then
* to your computer via USB. After uploading this program to
* your Arduino, open the Serial Monitor. Press the button on
* the HamShield to begin setup. After setup is complete, type
* your desired Tx/Rx frequency, in hertz, into the bar at the
* top of the Serial Monitor and click the "Send" button.
* To test with another HandyTalkie (HT), key up on your HT
* and make sure you can hear it through the headphones
* attached to the HamShield. Key up on the HamShield by
* holding the button.
*/
// Hamshield
#include <HamShield.h>
// create object for radio
HamShield radio;
// To use non-standard pins, use the following initialization
//HamShield radio(ncs_pin, clk_pin, dat_pin);
#define LED_PIN 13
#define RSSI_REPORT_RATE_MS 5000
#define MIC_PIN 3
//TODO: move these into library
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
@ -39,47 +22,44 @@ unsigned long rssi_timeout;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW);
// initialize serial communication
Serial.begin(9600);
Serial.println("press the switch or send any character to begin...");
Serial.println("press the switch to begin...");
while (digitalRead(SWITCH_PIN) && !Serial.available());
Serial.read(); // flush
while (digitalRead(SWITCH_PIN));
// let the radio out of reset
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
// let the AU ot of reset
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.println("beginning radio setup");
// verify connection
Serial.println("Testing device connections...");
Serial.println(radio.testConnection() ? "radio connection successful" : "radio connection failed");
Serial.println(radio.testConnection() ? "RDA radio connection successful" : "RDA radio connection failed");
// initialize device
Serial.println("Initializing radio device...");
Serial.println("Initializing I2C devices...");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration");
radio.dangerMode();
// set frequency
Serial.println("changing frequency");
radio.setSQOff();
freq = 432100; // 70cm calling frequency
freq = 446000;
radio.frequency(freq);
// set to receive
@ -137,7 +117,7 @@ void loop() {
} else {
Serial.setTimeout(40);
freq = Serial.parseInt();
while (Serial.available()) Serial.read();
Serial.flush();
radio.frequency(freq);
Serial.print("set frequency: ");
Serial.println(freq);

View File

@ -1,283 +0,0 @@
/* Hamshield
* Example: HandyTalkie_nRF52840
* This is a simple example to demonstrate the HamShield working
* with an Adafruit Feather nRF52840 Express
*
* HamShield to Feather Connections:
* SPKR - Feather A0
* MIC - Feather D11
* CLK - Feather D5
* nCS - Feather D6
* DAT - Feather D9
* GND - Feather GND
* VCC - Feather 3.3V
*
* Connect the HamShield to your Feather as above.
* Screw the antenna into the HamShield RF jack. Plug a pair
* of headphones into the HamShield.
*
* Connect the Feather nRF52840 Express to your computer via
* a USB Micro B cable. After uploading this program to
* your Feather, open the Serial Monitor. You should see some
* text displayed that documents the setup process.
*
* Once the Feather is set up and talking to the HamShield,
* you can control it over USB-Serial or BLE-Serial(UART).
*
* Try using Adafruit's Bluefruit app to connect to the Feather.
* Once you're connected, you can control the HamShield using
* the same commands you'd use over USB-Serial. The response to
* all commands will be echoed to both USB-Serial and BLE-Serial(UART).
*
* Serial UART commands:
* t - change from Tx to Rx (or vice versa)
* F123400 - set frequency to 123400 kHz
*/
#include <bluefruit.h>
// BLE Service
BLEDis bledis; // device information
BLEUart bleuart; // uart over ble
BLEBas blebas; // battery
#include <HamShield.h>
// create object for radio
HamShield radio(6,5,9);
// To use non-standard pins, use the following initialization
//HamShield radio(ncs_pin, clk_pin, dat_pin);
#define LED_PIN 3
#define RSSI_REPORT_RATE_MS 5000
#define MIC_PIN A1
bool blinkState = false;
bool currently_tx;
uint32_t freq;
unsigned long rssi_timeout;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// initialize serial communication
Serial.begin(115200);
while (!Serial) delay(10);
Serial.println("Setting up BLE");
// Setup the BLE LED to be enabled on CONNECT
// Note: This is actually the default behaviour, but provided
// here in case you want to control this LED manually via PIN 19
Bluefruit.autoConnLed(true);
// Config the peripheral connection with maximum bandwidth
// more SRAM required by SoftDevice
// Note: All config***() function must be called before begin()
Bluefruit.configPrphBandwidth(BANDWIDTH_MAX);
Bluefruit.begin();
// Set max power. Accepted values are: -40, -30, -20, -16, -12, -8, -4, 0, 4
Bluefruit.setTxPower(4);
Bluefruit.setName("MyBlueHam");
//Bluefruit.setName(getMcuUniqueID()); // useful testing with multiple central connections
Bluefruit.setConnectCallback(connect_callback);
Bluefruit.setDisconnectCallback(disconnect_callback);
// Configure and Start Device Information Service
bledis.setManufacturer("Enhanced Radio Devices");
bledis.setModel("BlueHam");
bledis.begin();
// Configure and Start BLE Uart Service
bleuart.begin();
// Start BLE Battery Service
blebas.begin();
blebas.write(100);
// Set up and start advertising
startAdv();
delay(100);
Serial.println("beginning Ham radio setup");
// verify connection
Serial.println("Testing device connections...");
if (radio.testConnection()) {
Serial.println("HamShield connection successful");
} else {
Serial.print("HamShield connection failed");
while(1) delay(100);
}
// initialize device
Serial.println("Initializing radio device...");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration");
// set frequency
Serial.println("changing frequency");
radio.setSQOff();
freq = 432100; // 70cm calling frequency
radio.frequency(freq);
// set to receive
radio.setModeReceive();
currently_tx = false;
Serial.print("config register is: ");
Serial.println(radio.readCtlReg());
Serial.println(radio.readRSSI());
/*
// set to transmit
radio.setModeTransmit();
// maybe set PA bias voltage
Serial.println("configured for transmit");
radio.setTxSourceMic();
*/
radio.setRfPower(0);
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, HIGH);
rssi_timeout = 0;
}
void startAdv(void)
{
// Advertising packet
Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE);
Bluefruit.Advertising.addTxPower();
// Include bleuart 128-bit uuid
Bluefruit.Advertising.addService(bleuart);
// Secondary Scan Response packet (optional)
// Since there is no room for 'Name' in Advertising packet
Bluefruit.ScanResponse.addName();
/* Start Advertising
* - Enable auto advertising if disconnected
* - Interval: fast mode = 20 ms, slow mode = 152.5 ms
* - Timeout for fast mode is 30 seconds
* - Start(timeout) with timeout = 0 will advertise forever (until connected)
*
* For recommended advertising interval
* https://developer.apple.com/library/content/qa/qa1931/_index.html
*/
Bluefruit.Advertising.restartOnDisconnect(true);
Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms
Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode
Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds
}
// for serial output buffer on both interfaces
#define TEXT_BUF_LEN 64
char text_buf[TEXT_BUF_LEN];
void loop() {
char c = 0;
bool ble_serial = false;
if (Serial.available()) {
Serial.readBytes(&c, 1);
} else if (bleuart.available()) {
c = (char) bleuart.read();
ble_serial = true;
}
if (c != 0) {
if (c == 't')
{
if (!currently_tx)
{
currently_tx = true;
// set to transmit
radio.setModeTransmit();
Serial.println("Tx");
int str_len = snprintf(text_buf, TEXT_BUF_LEN, "Tx\n");
bleuart.write(text_buf, str_len);
//radio.setTxSourceMic();
//radio.setRfPower(1);
} else {
radio.setModeReceive();
currently_tx = false;
Serial.println("Rx");
int str_len = snprintf(text_buf, TEXT_BUF_LEN, "Rx\n");
bleuart.write(text_buf, str_len);
}
} else if (c == 'F') {
if (ble_serial == false) {
Serial.setTimeout(40);
freq = Serial.parseInt();
Serial.flush();
} else {
int idx = 0;
while (bleuart.available() &&
bleuart.peek() >= '0' &&
bleuart.peek() <= '9' &&
idx < TEXT_BUF_LEN) {
text_buf[idx] = bleuart.read();
idx++;
}
text_buf[idx] = 0; // null terminate
freq = atoi(text_buf);
}
radio.frequency(freq);
Serial.print("set frequency: ");
Serial.println(freq);
int str_len = snprintf(text_buf, TEXT_BUF_LEN, "set frequency: %d\n", freq);
bleuart.write(text_buf, str_len);
}
}
if (!currently_tx && (millis() - rssi_timeout) > RSSI_REPORT_RATE_MS)
{
int rssi = radio.readRSSI();
Serial.println(rssi);
int str_len = snprintf(text_buf, TEXT_BUF_LEN, "rssi: %d\n", rssi);
bleuart.write(text_buf, str_len);
rssi_timeout = millis();
}
}
// callback invoked when central connects
void connect_callback(uint16_t conn_handle)
{
char central_name[32] = { 0 };
Bluefruit.Gap.getPeerName(conn_handle, central_name, sizeof(central_name));
Serial.print("Connected to ");
Serial.println(central_name);
}
/**
* Callback invoked when a connection is dropped
* @param conn_handle connection where this event happens
* @param reason is a BLE_HCI_STATUS_CODE which can be found in ble_hci.h
* https://github.com/adafruit/Adafruit_nRF52_Arduino/blob/master/cores/nRF5/nordic/softdevice/s140_nrf52_6.1.1_API/include/ble_hci.h
*/
void disconnect_callback(uint16_t conn_handle, uint8_t reason)
{
(void) conn_handle;
(void) reason;
Serial.println();
Serial.println("Disconnected");
}

View File

@ -0,0 +1,95 @@
/*
Indentifier
Arduino audio overlay example
*/
#include <HamShield.h>
#define DOT 100
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
const char *bascii = "ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789.,?'!/()&:;=+-_\"$@",
*bitu[] = { ".-","-...","-.-.","-..",".","..-.","--.","....","..",".---","-.-",".-..","--","-.","---",".--.","--.-",".-.","...","-","..-","...-",".--","-..-","-.--","--..","-----",".----","..---","...--","....-",".....","-....","--...","---..","----.",".-.-.-","--..--","..--..",".----.","-.-.--","-..-.","-.--.","-.--.-",".-...","---...","-.-.-.","-...-",".-.-.","-....-","..--.-",".-..-.","...-..-",".--.-."
};
const char *callsign = {"1ZZ9ZZ/B"} ;
char morsebuffer[8];
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
Serial.println("starting up..");
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
radio.initialize();
radio.frequency(446000);
radio.setVolume1(0xF);
radio.setVolume2(0xF);
radio.setModeReceive();
radio.setTxSourceMic();
radio.setSQLoThresh(80);
radio.setSQOn();
Serial.println("Done with radio beacon setup. Press and hold a key to transmit.");
}
int state = 0;
long timer = 0;
int morseletter = 0;
int morsesymbol = 0;
long keyer = 0;
char symbol;
void loop() {
if(Serial.available() > 0) {
if(state == 0) {
state = 10;
radio.setModeTransmit();
timer = millis();
keyer = millis();
}
if(state == 10) {
timer = millis();
}
}
if(millis() > (timer + 500)) { radio.setModeReceive(); morseletter = 0; morsesymbol = 0; state = 0; }
if(state == 10) {
if(millis() > (keyer + (DOT * 3))) {
keyer = millis();
symbol = lookup(callsign[morseletter],morsesymbol);
if(symbol == '-') { tone(9,1000,DOT*3); }
if(symbol == '.') { tone(9,1000,DOT); }
if(symbol == 0) { morsesymbol = 0; morseletter++; }
if(callsign[morseletter] == 0) { morsesymbol = 0; morseletter = 0; }
}
}
}
char lookup(char letter, int morsesymbol) {
for(int x = 0; x < 54; x++) {
if(letter == bascii[x]) {
return bitu[x][morsesymbol];
}
}
}

View File

@ -0,0 +1,41 @@
/* Just Transmit */
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
Serial.println("If the sketch freezes at radio status, there is something wrong with power or the shield");
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
Serial.println("Setting radio to its defaults..");
radio.initialize();
radio.setRfPower(0);
radio.setChanMode(3);
}
void loop() {
radio.bypassPreDeEmph();
radio.frequency(144000);
// radio.setTxSourceNone();
radio.setModeTransmit();
for(;;) { }
}

View File

@ -1,95 +1,47 @@
/* Hamshield
* Example: KISS
* This is a example configures the HamShield to be used as
* a TNC/KISS device. You will need a KISS device to input
* commands to the HamShield
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. Issue commands
* via the KISS equipment.
*
* You can also just use the serial terminal to send and receive
* APRS packets, but keep in mind that several fields in the packet
* are bit-shifted from standard ASCII (so if you're receiving,
* you won't get human readable callsigns or paths).
*
* To use the KISS example with YAAC:
* 1. open the configure YAAC wizard
* 2. follow the prompts and enter in your details until you get to the "Add and Configure Interfaces" window
* 3. Choose "Add Serial KISS TNC Port"
* 4. Choose the COM port for your Arduino
* 5. set baud rate to 9600 (default)
* 6. set it to KISS-only: with no command to enter KISS mode (just leave the box empty)
* 7. Use APRS protocol (default)
* 8. hit the next button and follow directions to finish configuration
*/
#include <HamShield.h>
#include <KISS.h>
#include <DDS.h>
#include <packet.h>
#include <avr/wdt.h>
HamShield radio;
DDS dds;
AFSK afsk;
KISS kiss(&Serial, &radio, &dds, &afsk);
KISS kiss(&Serial, &radio, &dds);
#define MIC_PIN 3
//TODO: move these into library
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
digitalWrite(RESET_PIN, LOW);
Serial.begin(9600);
while (digitalRead(SWITCH_PIN));
// let the AU ot of reset
digitalWrite(RESET_PIN, HIGH);
radio.initialize();
//radio.setSQOff();
radio.setVolume1(0xFF);
radio.setVolume2(0xFF);
radio.setSQHiThresh(-100);
radio.setSQLoThresh(-100);
//radio.setSQOn();
radio.setSQOff();
radio.frequency(144390);
radio.bypassPreDeEmph();
//I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x44, 0x05FF);
dds.start();
afsk.start(&dds);
delay(100);
radio.setModeReceive();
radio.afsk.start(&dds);
}
void loop() {
kiss.loop();
}
ISR(TIMER2_OVF_vect) {
TIFR2 = _BV(TOV2);
static uint8_t tcnt = 0;
if(++tcnt == 8) {
dds.clockTick();
tcnt = 0;
}
}
ISR(ADC_vect) {
static uint8_t tcnt = 0;
TIFR1 = _BV(ICF1); // Clear the timer flag
dds.clockTick();
if(++tcnt == 1) {
afsk.timer();
tcnt = 0;
}
}
kiss.isr();
}

View File

@ -1,128 +0,0 @@
/* Hamshield
* Example: Morse Code Transceiver
*
* Serial to Morse transceiver. Sends characters from the Serial
* port over the air, and vice versa.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. After uploading
* this program to your Arduino, open the Serial Monitor to
* monitor the status of the beacon. To test, set a HandyTalkie
* to 438MHz. You should hear the message " CALLSIGN HAMSHIELD"
* in morse code.
*
*
* Note: only upper case letters, numbers, and a few symbols
* are supported.
* Supported symbols: &/+(=:?";@`-._),!$
*
* If you're having trouble accurately decoding, you may want to
* tweak the min/max . and - times. You can also uncomment
* the Serial.print debug statements that can tell you when tones
* are being detected, how long they're detected for, and whether
* the tones are decoded as a . or -.
*
*/
#define DDS_REFCLK_DEFAULT 9600
#include <HamShield.h>
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
#define MORSE_FREQ 600
#define MORSE_DOT 150 // ms
// Note that all timing is defined in terms of MORSE_DOT relative durations
// You may want to tweak those timings below
HamShield radio;
// Run our start up things here
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
// Set up the serial port at 9600 Baud
Serial.begin(9600);
// Send a quick serial string
Serial.println("HamShield Morse Example Sketch");
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
// Tell the HamShield to start up
radio.initialize();
// Set the transmit power level (0-8)
radio.setRfPower(0);
// Set the morse code characteristics
radio.setMorseFreq(MORSE_FREQ);
radio.setMorseDotMillis(MORSE_DOT);
radio.lookForTone(MORSE_FREQ);
radio.setupMorseRx();
// Configure the HamShield frequency
radio.frequency(432100); // 70cm calling frequency
radio.setModeReceive();
Serial.println("Radio Configured.");
}
void loop() {
char rx_char = radio.morseRxLoop();
if (rx_char != 0) {
Serial.print(rx_char);
}
// should we send anything
if (Serial.available()) {
Serial.println("checking channel");
// We'll wait up to 30 seconds for a clear channel, requiring that the channel is clear for 2 seconds before we transmit
if (radio.waitForChannel(30000,2000,-5)) {
// If we get here, the channel is clear.
Serial.println("sending");
// Start transmitting by putting the radio into transmit mode.
radio.setModeTransmit();
Serial.println("tx");
unsigned int MORSE_BUF_SIZE = 128;
char morse_buf[MORSE_BUF_SIZE];
unsigned int morse_idx;
morse_buf[morse_idx++] = ' '; // start with space to let PA come up
while (Serial.available() && morse_idx < MORSE_BUF_SIZE) {
morse_buf[morse_idx++] = Serial.read();
}
morse_buf[morse_idx] = '\0'; // null terminate
// Send a message out in morse code
radio.morseOut(morse_buf);
// We're done sending the message, set the radio back into recieve mode.
Serial.println("sent");
radio.setModeReceive();
radio.lookForTone(MORSE_FREQ);
} else {
// If we get here, the channel is busy. Let's also print out the RSSI.
Serial.print("The channel was busy. RSSI: ");
Serial.println(radio.readRSSI());
}
}
}

View File

@ -0,0 +1,105 @@
#include <HamShield.h>
#include "varicode.h"
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
DDS dds;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
// put your setup code here, to run once:
dds.setReferenceClock(32000);
dds.start();
dds.setFrequency(1000);
dds.on();
}
volatile bool sent = true;
volatile uint16_t bitsToSend = 0;
volatile uint8_t zeroCount = 0;
void sendChar(uint8_t c) {
uint16_t bits = varicode[c];
while((bits&0x8000)==0) {
bits<<=1;
}
while(!sent) {} //delay(32);
cli();
sent = false;
bitsToSend = bits;
sei();
while(!sent) {} //delay(32);
//PORTD &= ~_BV(2); // Diagnostic pin (D2)
}
char *string = "Why hello there, friend. Nice to meet you. Welcome to PSK31. 73, VE6SLP sk\r\n";
void loop() {
int i;
// put your main code here, to run repeatedly:
//for(i = 0; i<5; i++)
// sendChar(0);
// return;
for(i = 0; i < strlen(string); i++) {
sendChar(string[i]);
//Serial.println(string[i]);
}
}
const uint8_t amplitudeShape[41] = {
255, 241, 228, 215, 203, 191, 181, 171, 161, 152, 143, 135, 128, 121, 114, 107, 101, 96, 90, 85, 80, 76, 72, 68, 64, 60, 57, 54, 51, 48, 45, 42, 40, 38, 36, 34, 32, 30, 28, 27, 25
};
// This will trigger at 8kHz
ISR(ADC_vect) {
static uint8_t outer = 0;
static uint8_t tcnt = 0;
TIFR1 |= _BV(ICF1);
// Wave shaping
// TODO: Improve how this would perform.
//else if(tcnt > (255-64))
// dds.setAmplitude((255 - tcnt));
//else dds.setAmplitude(255);
if(tcnt < 81)
dds.setAmplitude(amplitudeShape[(81-tcnt)/2]);
if(tcnt > (255-81))
dds.setAmplitude(amplitudeShape[(tcnt-174)/2]);
dds.clockTick();
//PORTD &= ~_BV(2);
if(outer++ == 3) {
outer = 0;
} else {
return;
}
if(tcnt++ == 0) { // Next bit
//PORTD ^= _BV(2); // Diagnostic pin (D2)
if(!sent) {
if((bitsToSend & 0x8000) == 0) {
zeroCount++;
dds.changePhaseDeg(+180);
} else {
zeroCount = 0;
}
bitsToSend<<=1;
if(zeroCount == 2) {
sent = true;
}
} else {
// Idle on zeroes
dds.changePhaseDeg(+180);
}
}
//PORTD &= ~_BV(2);
}

View File

@ -0,0 +1,130 @@
const uint16_t varicode[] = {
0xAAC0, // ASCII = 0 1010101011
0xB6C0, // ASCII = 1 1011011011
0xBB40, // ASCII = 2 1011101101
0xDDC0, // ASCII = 3 1101110111
0xBAC0, // ASCII = 4 1011101011
0xD7C0, // ASCII = 5 1101011111
0xBBC0, // ASCII = 6 1011101111
0xBF40, // ASCII = 7 1011111101
0xBFC0, // ASCII = 8 1011111111
0xEF00, // ASCII = 9 11101111
0xE800, // ASCII = 10 11101
0xDBC0, // ASCII = 11 1101101111
0xB740, // ASCII = 12 1011011101
0xF800, // ASCII = 13 11111
0xDD40, // ASCII = 14 1101110101
0xEAC0, // ASCII = 15 1110101011
0xBDC0, // ASCII = 16 1011110111
0xBD40, // ASCII = 17 1011110101
0xEB40, // ASCII = 18 1110101101
0xEBC0, // ASCII = 19 1110101111
0xD6C0, // ASCII = 20 1101011011
0xDAC0, // ASCII = 21 1101101011
0xDB40, // ASCII = 22 1101101101
0xD5C0, // ASCII = 23 1101010111
0xDEC0, // ASCII = 24 1101111011
0xDF40, // ASCII = 25 1101111101
0xEDC0, // ASCII = 26 1110110111
0xD540, // ASCII = 27 1101010101
0xD740, // ASCII = 28 1101011101
0xEEC0, // ASCII = 29 1110111011
0xBEC0, // ASCII = 30 1011111011
0xDFC0, // ASCII = 31 1101111111
0x8000, // ASCII = ' ' 1
0xFF80, // ASCII = '!' 111111111
0xAF80, // ASCII = '"' 101011111
0xFA80, // ASCII = '#' 111110101
0xED80, // ASCII = '$' 111011011
0xB540, // ASCII = '%' 1011010101
0xAEC0, // ASCII = '&' 1010111011
0xBF80, // ASCII = ''' 101111111
0xFB00, // ASCII = '(' 11111011
0xF700, // ASCII = ')' 11110111
0xB780, // ASCII = '*' 101101111
0xEF80, // ASCII = '+' 111011111
0xEA00, // ASCII = ',' 1110101
0xD400, // ASCII = '-' 110101
0xAE00, // ASCII = '.' 1010111
0xD780, // ASCII = '/' 110101111
0xB700, // ASCII = '0' 10110111
0xBD00, // ASCII = '1' 10111101
0xED00, // ASCII = '2' 11101101
0xFF00, // ASCII = '3' 11111111
0xBB80, // ASCII = '4' 101110111
0xAD80, // ASCII = '5' 101011011
0xB580, // ASCII = '6' 101101011
0xD680, // ASCII = '7' 110101101
0xD580, // ASCII = '8' 110101011
0xDB80, // ASCII = '9' 110110111
0xF500, // ASCII = ':' 11110101
0xDE80, // ASCII = ';' 110111101
0xF680, // ASCII = '<' 111101101
0xAA00, // ASCII = '=' 1010101
0xEB80, // ASCII = '>' 111010111
0xABC0, // ASCII = '?' 1010101111
0xAF40, // ASCII = '@' 1010111101
0xFA00, // ASCII = 'A' 1111101
0xEB00, // ASCII = 'B' 11101011
0xAD00, // ASCII = 'C' 10101101
0xB500, // ASCII = 'D' 10110101
0xEE00, // ASCII = 'E' 1110111
0xDB00, // ASCII = 'F' 11011011
0xFD00, // ASCII = 'G' 11111101
0xAA80, // ASCII = 'H' 101010101
0xFE00, // ASCII = 'I' 1111111
0xFE80, // ASCII = 'J' 111111101
0xBE80, // ASCII = 'K' 101111101
0xD700, // ASCII = 'L' 11010111
0xBB00, // ASCII = 'M' 10111011
0xDD00, // ASCII = 'N' 11011101
0xAB00, // ASCII = 'O' 10101011
0xD500, // ASCII = 'P' 11010101
0xEE80, // ASCII = 'Q' 111011101
0xAF00, // ASCII = 'R' 10101111
0xDE00, // ASCII = 'S' 1101111
0xDA00, // ASCII = 'T' 1101101
0xAB80, // ASCII = 'U' 101010111
0xDA80, // ASCII = 'V' 110110101
0xAE80, // ASCII = 'W' 101011101
0xBA80, // ASCII = 'X' 101110101
0xBD80, // ASCII = 'Y' 101111011
0xAB40, // ASCII = 'Z' 1010101101
0xFB80, // ASCII = '[' 1111101110
0xF780, // ASCII = '\' 111101111
0xFD80, // ASCII = ']' 111111011
0xAFC0, // ASCII = '^' 1010111111
0xB680, // ASCII = '_' 101101101
0xB7C0, // ASCII = '`' 1011011111
0xB000, // ASCII = 'a' 1011
0xBE00, // ASCII = 'b' 1011111
0xBC00, // ASCII = 'c' 101111
0xB400, // ASCII = 'd' 101101
0xC000, // ASCII = 'e' 11
0xF400, // ASCII = 'f' 111101
0xB600, // ASCII = 'g' 1011011
0xAC00, // ASCII = 'h' 101011
0xD000, // ASCII = 'i' 1101
0xF580, // ASCII = 'j' 111101011
0xBF00, // ASCII = 'k' 10111111
0xD800, // ASCII = 'l' 11011
0xEC00, // ASCII = 'm' 111011
0xF000, // ASCII = 'n' 1111
0xE000, // ASCII = 'o' 111
0xFC00, // ASCII = 'p' 111111
0xDF80, // ASCII = 'q' 110111111
0xA800, // ASCII = 'r' 10101
0xB800, // ASCII = 's' 10111
0xA000, // ASCII = 't' 101
0xDC00, // ASCII = 'u' 110111
0xF600, // ASCII = 'v' 1111011
0xD600, // ASCII = 'w' 1101011
0xDF00, // ASCII = 'x' 11011111
0xBA00, // ASCII = 'y' 1011101
0xEA80, // ASCII = 'z' 111010101
0xADC0, // ASCII = '{' 1010110111
0xDD80, // ASCII = '|' 110111011
0xAD40, // ASCII = '}' 1010110101
0xB5C0, // ASCII = '~' 1011010111
0xED40 // ASCII = 127 1110110101
};

124
examples/Parrot/Parrot.ino Executable file
View File

@ -0,0 +1,124 @@
/*
Record sound and then plays it back a few times.
Very low sound quality @ 2KHz 0.75 seconds
A bit robotic and weird
*/
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
#define RATE 500
#define SIZE 1500
HamShield radio;
char sound[SIZE];
unsigned int sample1;
int x = -1;
int16_t rssi;
byte mode = 8;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
// int result = radio.testConnection();
radio.initialize();
radio.setFrequency(446000);
setPwmFrequency(9, 1);
}
void loop() {
rssi = radio.readRSSI();
if(rssi > -100) {
if(x == -1) {
for(x = 0; x < SIZE; x++) {
if(mode == 4) {
sample1 = analogRead(0);
sound[x] = sample1 >> 4;
delayMicroseconds(RATE); x++;
sample1 = analogRead(0);
sound[x] = (sample1 & 0xF0) | sound[x];
delayMicroseconds(RATE);
} else {
sound[x] = analogRead(0);
delayMicroseconds(RATE); x++;
sound[x] = analogRead(0);
delayMicroseconds(RATE);
}
}
}
}
if(rssi < -100) {
if(x == 1500) {
radio.setModeTransmit();
delay(500);
tone(9,1000,500); delay(750);
for(int r = 0; r < 10; r++) {
for(x = 0; x < SIZE; x++) {
if(mode == 4) {
analogWrite(9,sound[x] << 4);
delayMicroseconds(RATE); x++;
analogWrite(9,sound[x] & 0xF);
delayMicroseconds(RATE); } else {
analogWrite(9,sound[x]);
delayMicroseconds(RATE); x++;
analogWrite(9,sound[x]);
delayMicroseconds(RATE);
}
} }
tone(9,1000,500); delay(750);
radio.setModeReceive();
x = -1;
}
}
}
void setPwmFrequency(int pin, int divisor) {
byte mode;
if(pin == 5 || pin == 6 || pin == 9 || pin == 10) {
switch(divisor) {
case 1: mode = 0x01; break;
case 8: mode = 0x02; break;
case 64: mode = 0x03; break;
case 256: mode = 0x04; break;
case 1024: mode = 0x05; break;
default: return;
}
if(pin == 5 || pin == 6) {
TCCR0B = TCCR0B & 0b11111000 | mode;
} else {
TCCR1B = TCCR1B & 0b11111000 | mode;
}
} else if(pin == 3 || pin == 11) {
switch(divisor) {
case 1: mode = 0x01; break;
case 8: mode = 0x02; break;
case 32: mode = 0x03; break;
case 64: mode = 0x04; break;
case 128: mode = 0x05; break;
case 256: mode = 0x06; break;
case 1024: mode = 0x7; break;
default: return;
}
TCCR2B = TCCR2B & 0b11111000 | mode;
}
}

View File

@ -0,0 +1,111 @@
#include <HamShield.h>
#include "varicode.h"
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
DDS dds;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW);
Serial.begin(9600);
// put your setup code here, to run once:
dds.setReferenceClock(32000);
dds.start();
dds.setFrequency(1000);
dds.on();
}
volatile bool sent = true;
volatile uint16_t bitsToSend = 0;
volatile uint8_t zeroCount = 0;
void sendChar(uint8_t c) {
uint16_t bits = varicode[c];
while((bits&0x8000)==0) {
bits<<=1;
}
while(!sent) {} //delay(32);
cli();
sent = false;
bitsToSend = bits;
sei();
while(!sent) {} //delay(32);
//PORTD &= ~_BV(2); // Diagnostic pin (D2)
}
char *string = "Why hello there, friend. Nice to meet you. Welcome to PSK31. 73, VE6SLP sk\r\n";
void loop() {
int i;
// put your main code here, to run repeatedly:
//for(i = 0; i<5; i++)
// sendChar(0);
// return;
for(i = 0; i < strlen(string); i++) {
sendChar(string[i]);
//Serial.println(string[i]);
}
}
const uint8_t amplitudeShape[41] = {
255, 241, 228, 215, 203, 191, 181, 171, 161, 152, 143, 135, 128, 121, 114, 107, 101, 96, 90, 85, 80, 76, 72, 68, 64, 60, 57, 54, 51, 48, 45, 42, 40, 38, 36, 34, 32, 30, 28, 27, 25
};
// This will trigger at 8kHz
const uint16_t qpskConvolution[32] = {
180, 90, -90, 0, -90, 0, 180, 90,
0, -90, 90, 180, 90, 180, 0, -90,
90, 180, 0, -90, 0, -90, 90, 180,
-90, 0, 180, 90, 180, 90, -90, 0
};
uint8_t last5Bits = 0b00000;
ISR(ADC_vect) {
static uint8_t outer = 0;
static uint8_t tcnt = 0;
TIFR1 |= _BV(ICF1);
// Wave shaping
// TODO: Improve how this would perform.
if(tcnt < 81)
dds.setAmplitude(amplitudeShape[(81-tcnt)/2]);
if(tcnt > (255-81))
dds.setAmplitude(amplitudeShape[(tcnt-174)/2]);
dds.clockTick();
if(outer++ == 1) {
outer = 0;
} else {
return;
}
if(tcnt++ == 0) { // Next bit
last5Bits <<= 1;
if(!sent) {
if((bitsToSend & 0x8000) == 0) {
zeroCount++;
} else {
zeroCount = 0;
last5Bits |= 1;
}
dds.changePhaseDeg(qpskConvolution[last5Bits&31]);
bitsToSend<<=1;
if(zeroCount == 2) {
sent = true;
}
} else {
// Idle on zeroes
dds.changePhaseDeg(qpskConvolution[last5Bits&31]);
}
}
}

View File

@ -0,0 +1,130 @@
const uint16_t varicode[] = {
0xAAC0, // ASCII = 0 1010101011
0xB6C0, // ASCII = 1 1011011011
0xBB40, // ASCII = 2 1011101101
0xDDC0, // ASCII = 3 1101110111
0xBAC0, // ASCII = 4 1011101011
0xD7C0, // ASCII = 5 1101011111
0xBBC0, // ASCII = 6 1011101111
0xBF40, // ASCII = 7 1011111101
0xBFC0, // ASCII = 8 1011111111
0xEF00, // ASCII = 9 11101111
0xE800, // ASCII = 10 11101
0xDBC0, // ASCII = 11 1101101111
0xB740, // ASCII = 12 1011011101
0xF800, // ASCII = 13 11111
0xDD40, // ASCII = 14 1101110101
0xEAC0, // ASCII = 15 1110101011
0xBDC0, // ASCII = 16 1011110111
0xBD40, // ASCII = 17 1011110101
0xEB40, // ASCII = 18 1110101101
0xEBC0, // ASCII = 19 1110101111
0xD6C0, // ASCII = 20 1101011011
0xDAC0, // ASCII = 21 1101101011
0xDB40, // ASCII = 22 1101101101
0xD5C0, // ASCII = 23 1101010111
0xDEC0, // ASCII = 24 1101111011
0xDF40, // ASCII = 25 1101111101
0xEDC0, // ASCII = 26 1110110111
0xD540, // ASCII = 27 1101010101
0xD740, // ASCII = 28 1101011101
0xEEC0, // ASCII = 29 1110111011
0xBEC0, // ASCII = 30 1011111011
0xDFC0, // ASCII = 31 1101111111
0x8000, // ASCII = ' ' 1
0xFF80, // ASCII = '!' 111111111
0xAF80, // ASCII = '"' 101011111
0xFA80, // ASCII = '#' 111110101
0xED80, // ASCII = '$' 111011011
0xB540, // ASCII = '%' 1011010101
0xAEC0, // ASCII = '&' 1010111011
0xBF80, // ASCII = ''' 101111111
0xFB00, // ASCII = '(' 11111011
0xF700, // ASCII = ')' 11110111
0xB780, // ASCII = '*' 101101111
0xEF80, // ASCII = '+' 111011111
0xEA00, // ASCII = ',' 1110101
0xD400, // ASCII = '-' 110101
0xAE00, // ASCII = '.' 1010111
0xD780, // ASCII = '/' 110101111
0xB700, // ASCII = '0' 10110111
0xBD00, // ASCII = '1' 10111101
0xED00, // ASCII = '2' 11101101
0xFF00, // ASCII = '3' 11111111
0xBB80, // ASCII = '4' 101110111
0xAD80, // ASCII = '5' 101011011
0xB580, // ASCII = '6' 101101011
0xD680, // ASCII = '7' 110101101
0xD580, // ASCII = '8' 110101011
0xDB80, // ASCII = '9' 110110111
0xF500, // ASCII = ':' 11110101
0xDE80, // ASCII = ';' 110111101
0xF680, // ASCII = '<' 111101101
0xAA00, // ASCII = '=' 1010101
0xEB80, // ASCII = '>' 111010111
0xABC0, // ASCII = '?' 1010101111
0xAF40, // ASCII = '@' 1010111101
0xFA00, // ASCII = 'A' 1111101
0xEB00, // ASCII = 'B' 11101011
0xAD00, // ASCII = 'C' 10101101
0xB500, // ASCII = 'D' 10110101
0xEE00, // ASCII = 'E' 1110111
0xDB00, // ASCII = 'F' 11011011
0xFD00, // ASCII = 'G' 11111101
0xAA80, // ASCII = 'H' 101010101
0xFE00, // ASCII = 'I' 1111111
0xFE80, // ASCII = 'J' 111111101
0xBE80, // ASCII = 'K' 101111101
0xD700, // ASCII = 'L' 11010111
0xBB00, // ASCII = 'M' 10111011
0xDD00, // ASCII = 'N' 11011101
0xAB00, // ASCII = 'O' 10101011
0xD500, // ASCII = 'P' 11010101
0xEE80, // ASCII = 'Q' 111011101
0xAF00, // ASCII = 'R' 10101111
0xDE00, // ASCII = 'S' 1101111
0xDA00, // ASCII = 'T' 1101101
0xAB80, // ASCII = 'U' 101010111
0xDA80, // ASCII = 'V' 110110101
0xAE80, // ASCII = 'W' 101011101
0xBA80, // ASCII = 'X' 101110101
0xBD80, // ASCII = 'Y' 101111011
0xAB40, // ASCII = 'Z' 1010101101
0xFB80, // ASCII = '[' 1111101110
0xF780, // ASCII = '\' 111101111
0xFD80, // ASCII = ']' 111111011
0xAFC0, // ASCII = '^' 1010111111
0xB680, // ASCII = '_' 101101101
0xB7C0, // ASCII = '`' 1011011111
0xB000, // ASCII = 'a' 1011
0xBE00, // ASCII = 'b' 1011111
0xBC00, // ASCII = 'c' 101111
0xB400, // ASCII = 'd' 101101
0xC000, // ASCII = 'e' 11
0xF400, // ASCII = 'f' 111101
0xB600, // ASCII = 'g' 1011011
0xAC00, // ASCII = 'h' 101011
0xD000, // ASCII = 'i' 1101
0xF580, // ASCII = 'j' 111101011
0xBF00, // ASCII = 'k' 10111111
0xD800, // ASCII = 'l' 11011
0xEC00, // ASCII = 'm' 111011
0xF000, // ASCII = 'n' 1111
0xE000, // ASCII = 'o' 111
0xFC00, // ASCII = 'p' 111111
0xDF80, // ASCII = 'q' 110111111
0xA800, // ASCII = 'r' 10101
0xB800, // ASCII = 's' 10111
0xA000, // ASCII = 't' 101
0xDC00, // ASCII = 'u' 110111
0xF600, // ASCII = 'v' 1111011
0xD600, // ASCII = 'w' 1101011
0xDF00, // ASCII = 'x' 11011111
0xBA00, // ASCII = 'y' 1011101
0xEA80, // ASCII = 'z' 111010101
0xADC0, // ASCII = '{' 1010110111
0xDD80, // ASCII = '|' 110111011
0xAD40, // ASCII = '}' 1010110101
0xB5C0, // ASCII = '~' 1011010111
0xED40 // ASCII = 127 1110110101
};

View File

@ -1,16 +1,10 @@
/* Hamshield
* Example: SSTV
* This program will transmit a test pattern. You will need
* SSTV equipment to test the output.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. After uploading
* this program to your Arduino, open the Serial Monitor to
* view the status of the program. Tune your SSTV to
* 446MHz to receive the image output.
/*
Sends an SSTV test pattern
*/
#define MIC_PIN 3
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
@ -28,17 +22,15 @@ int16_t rssi;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.begin(9600);
Serial.print("Radio status: ");
@ -53,7 +45,7 @@ void setup() {
void loop() {
if(radio.waitForChannel(1000,2000, -90)) { // Wait forever for calling frequency to open, then wait 2 seconds for breakers
if(radio.waitForChannel(1000,2000)) { // Wait forever for calling frequency to open, then wait 2 seconds for breakers
radio.setModeTransmit(); // Turn on the transmitter
delay(250); // Wait a moment
radio.SSTVTestPattern(MARTIN1); // send a MARTIN1 test pattern

View File

@ -1,22 +1,9 @@
/* Hamshield
* Example: SSTV M1 Static
* This program will transmit a static image. You will need
* SSTV equipment to test the output.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to wall
* power and then to your computer via USB. After uploading
* this program to your Arduino, open the Serial Monitor to
* view the status of the program. Tune your SSTV to
* 145.5MHz to receive the image output.
*/
// So the precalculated values will get stored
#define DDS_REFCLK_DEFAULT (34965/2)
#include <HamShield.h>
#include <DDS.h>
#define MIC_PIN 3
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
@ -32,17 +19,15 @@ ddsAccumulator_t freqTable[3];
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.begin(9600);
@ -55,7 +40,7 @@ void setup() {
// Tell the HamShield to start up
radio.initialize();
radio.setRfPower(0);
radio.frequency(446000);
radio.frequency(145500);
// put your setup code here, to run once:
//dds.setReferenceClock(34965/4);
dds.start();

View File

@ -1,562 +1,225 @@
/* Hamshield
* Example: Serial Tranceiver
* SerialTransceiver is TTL Serial port "glue" to allow
* desktop or laptop control of the HamShield.
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Plug a pair of headphones into
* the HamShield. Connect the Arduino to wall power and then
* to your computer via USB. After uploading this program to
* your Arduino, open the Serial Monitor. Use the bar at the
* top of the serial monitor to enter commands as seen below.
*
* EXAMPLE: To change the repeater offset to 144.425MHz,
* enable offset, then key in, use the following commands:
* T144425;
* R1;
* [Just a space]
// see also: https://github.com/EnhancedRadioDevices/HamShield/wiki/HamShield-Serial-Mode
Commands:
Mode ASCII Description
-------------- ----------- --------------------------------------------------------------------------------------------------------------------------------------------
Transmit space Space must be received at least every 500 mS
Receive not space If space is not received and/or 500 mS timeout of space occurs, unit will go into receive mode
Frequency F<freq>; Set the receive frequency in KHz, if offset is disabled, this is the transmit frequency
Morse Out M<text>; A small buffer for morse code (32 chars)
Morse In N; Sets mode to Morse In, listening for Morse
Power level P<level>; Set the power amp level, 0 = lowest, 15 = highest
Enable Offset R<state>; 1 turns on repeater offset mode, 0 turns off repeater offset mode
Squelch S<level>; Set the squelch level
TX Offset T<freq>; The absolute frequency of the repeater offset to transmit on in KHz
RSSI ? Respond with the current receive level in - dBm (no sign provided on numerical response)
Voice Level ^ Respond with the current voice level (VSSI), only valid when transmitting
DTMF Out D<vals>; A small buffer for DTMF out (only 0-9,A,B,C,D,*,# accepted)
DTMF In B; Sets mode to DTMF In, listening for DTMF
PL Tone Tx A<val>; Sets PL tone for TX, value is tone frequency in Hz (float), set to 0 to disable
PL Tone Rx C<val>; Sets PL tone for RX, value is tone frequency in Hz (float), set to 0 to disable
Volume 1 V1<val>; Set volume 1 (value between 0 and 15)
Volume 2 V2<val>; Set volume 2 (value between 0 and 15)
KISS TNC K; Move to KISS TNC mode (send ^; to move back to normal mode). NOT IMPELEMENTED YET
Normal Mode _ Move to Normal mode from any other mode (except TX)
Responses:
Condition ASCII Description
------------ ---------- -----------------------------------------------------------------
Startup *<code>; Startup and shield connection status
Success !; Generic success message for command that returns no value
Error X<code>; Indicates an error code. The numerical value is the type of error
Value :<value>; In response to a query
Status #<value>; Unsolicited status message
Debug Msg @<text>; 32 character debug message
Rx Msg R<text>; up to 32 characters of received message, only if device is in DTMF or Morse Rx modes
*/
// Note that the following are not yet implemented
// TODO: change get_value so it's intuitive
// TODO: Squelch open and squelch shut independently controllable
// TODO: pre/de emph filter
// TODO: walkie-talkie
// TODO: KISS TNC
#include "HamShield.h"
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
enum {TX, NORMAL, DTMF, MORSE, KISS};
int state = NORMAL;
bool rx_ctcss = false;
bool muted = false;
int txcount = 0;
long timer = 0; // Transmit timer to track timeout (send space to reset)
long freq = 432100; // 70cm calling frequency, receive frequency and default transmit frequency
long tx_freq = 0; // transmit frequency if repeater is on
int pwr = 0; // tx power
char cmdbuff[32] = "";
int temp = 0;
bool repeater = false; // true if transmit and receive operate on different frequencies
char pl_rx_buffer[32]; // pl tone rx buffer
char pl_tx_buffer[32]; // pl tone tx buffer
float ctcssin = 0;
float ctcssout = 0;
int cdcssin = 0;
int cdcssout = 0;
HamShield radio;
void setup() {
// NOTE: if not using PWM out (MIC pin), it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Serial.begin(9600);
Serial.println(";;;;;;;;;;;;;;;;;;;;;;;;;;");
int result = radio.testConnection();
Serial.print("*");
Serial.print(result,DEC);
Serial.println(";");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
radio.frequency(freq);
radio.setVolume1(0xF);
radio.setVolume2(0xF);
radio.setModeReceive();
radio.setTxSourceMic();
radio.setRfPower(pwr);
radio.setSQLoThresh(-80);
radio.setSQHiThresh(-70);
radio.setSQOn();
Serial.println("*START;");
}
void loop() {
if(Serial.available()) {
int text = Serial.read(); // get the first char to see what the upcoming command is
switch (state) {
// we handle commands differently based on what state we're in
case TX:
// we're currently transmitting
// if we got a space, reset our transmit timeout
if(text == ' ') { timer = millis();}
break;
case NORMAL:
switch(text) {
case ' ': // space - transmit
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute (for PL tones) during tx
radio.setUnmute();
radio.setModeTransmit();
state = TX;
Serial.println("#TX,ON;");
timer = millis();
break;
case '?': // ? - RSSI
Serial.print(":");
Serial.print(radio.readRSSI(),DEC);
Serial.println(";");
break;
case '^': // ^ - VSSI (voice) level
Serial.print(":");
Serial.print(radio.readVSSI(),DEC);
Serial.println(";");
break;
case 'F': // F - frequency
getValue();
freq = atol(cmdbuff);
if(radio.frequency(freq) == true) {
Serial.print("@");
Serial.print(freq,DEC);
Serial.println(";!;");
} else {
Serial.println("X1;");
}
break;
case 'P': // P - power level
getValue();
temp = atol(cmdbuff);
radio.setRfPower(temp);
Serial.println("!;");
break;
case 'S': // S - squelch
getValue();
temp = atol(cmdbuff);
if (temp < -2 && temp > -130) {
radio.setSQLoThresh(temp);
radio.setSQHiThresh(temp+2);
radio.setSQOn();
Serial.print(temp);
Serial.println("!;");
} else {
Serial.println("X!;");
}
break;
case 'R': // R - repeater offset mode
getValue();
temp = atol(cmdbuff);
if(temp == 0) { repeater = 0; }
if(temp == 1) { repeater = 1; }
Serial.println("!;");
break;
case 'T': // T - transmit offset
getValue();
tx_freq = atol(cmdbuff);
Serial.println("!;");
break;
case 'M': // M - Morse
getValue();
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute (for PL tones) during tx
radio.setUnmute();
radio.setModeTransmit();
delay(300);
radio.morseOut(cmdbuff);
if(repeater == true) { radio.frequency(freq); }
radio.setModeReceive();
Serial.println("!;");
break;
case 'N': // N - set to Morse in Mode
morse_rx_setup();
state = MORSE;
Serial.println("!;");
break;
case 'D': // D - DTMF Out
dtmfSetup();
getValue();
dtmf_out(cmdbuff);
Serial.println("!;");
break;
case 'B': // B - set to DTMF in Mode
dtmfSetup();
radio.enableDTMFReceive();
state = DTMF;
Serial.println("!;");
break;
case 'A': // A - TX PL Tone configuration command
pl_tone_tx();
Serial.println("!;");
break;
case 'C': // C - RX PL Tone configuration command
pl_tone_rx();
Serial.println("!;");
break;
case 'V': // V - set volume
getValue();
temp = cmdbuff[0];
if (temp == 0x31) {
temp = atol(cmdbuff + 1);
radio.setVolume1(temp);
Serial.println("!;");
} else if (temp == 0x32) {
temp = atol(cmdbuff + 1);
radio.setVolume2(temp);
Serial.println("!;");
} else {
// not a valid volume command
while (Serial.available()) { Serial.read(); }
Serial.println("X!;");
}
break;
case 'K': // K - switch to KISS TNC mode
//state = KISS;
//TODO: set up KISS
Serial.println("X1;");
break;
default:
// unknown command, flush the input buffer and wait for next one
Serial.println("X1;");
while (Serial.available()) { Serial.read(); }
break;
}
break;
case KISS:
if (Serial.peek() == '_') {
state = NORMAL;
if (rx_ctcss) {
radio.enableCtcss();
muted = true; // can't mute (for PL tones) during tx
radio.setMute();
}
}
// TODO: handle KISS TNC
break;
case MORSE:
if (text == '_') { state = NORMAL; }
if (text == 'M') { // tx message
getValue();
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute (for PL tones) during tx
radio.setUnmute();
radio.setModeTransmit();
delay(300);
radio.morseOut(cmdbuff);
if(repeater == true) { radio.frequency(freq); }
radio.setModeReceive();
} else {
// not a valid cmd
while (Serial.available()) { Serial.read(); }
}
break;
case DTMF:
if (text == '_') { state = NORMAL; }
if (text == 'D') { // tx message
getValue();
dtmf_out(cmdbuff);
} else {
// not a valid cmd
while (Serial.available()) { Serial.read(); }
}
break;
default:
// we're in an invalid state, reset to safe settings
while (Serial.available()) { Serial.read(); }
radio.frequency(freq);
radio.setModeReceive();
state = NORMAL;
break;
}
}
// now handle any state related functions
switch (state) {
case TX:
if(millis() > (timer + 500)) {
Serial.println("#TX,OFF;");
radio.setModeReceive();
if(repeater == true) { radio.frequency(freq); }
if (rx_ctcss) {
radio.setMute();
muted = true;
}
txcount = 0;
state = NORMAL;
}
break;
case NORMAL:
// deal with rx ctccs if necessary
if (rx_ctcss) {
if (radio.getCtcssToneDetected()) {
if (muted) {
muted = false;
radio.setUnmute();
}
} else {
if (!muted) {
muted = true;
radio.setMute();
}
}
}
break;
case DTMF:
dtmf_rx(); // wait for DTMF reception
break;
case MORSE:
morse_rx(); // wait for Morse reception
break;
}
// get rid of any trailing whitespace in the serial buffer
if (Serial.available()) {
char cpeek = Serial.peek();
while (cpeek == ' ' || cpeek == '\r' || cpeek == '\n')
{
Serial.read();
cpeek = Serial.peek();
}
}
}
void getValue() {
int p = 0;
char temp;
for(;;) {
if(Serial.available()) {
temp = Serial.read();
if(temp == 59) {
cmdbuff[p] = 0;
return;
}
cmdbuff[p] = temp;
p++;
if(p == 32) {
cmdbuff[0] = 0;
return;
}
}
}
}
void dtmfSetup() {
radio.setVolume1(6);
radio.setVolume2(0);
radio.setDTMFDetectTime(24); // time to detect a DTMF code, units are 2.5ms
radio.setDTMFIdleTime(50); // time between transmitted DTMF codes, units are 2.5ms
radio.setDTMFTxTime(60); // duration of transmitted DTMF codes, units are 2.5ms
}
void dtmf_out(char * out_buf) {
if (out_buf[0] == ';' || out_buf[0] == 0) return; // empty message
uint8_t i = 0;
uint8_t code = radio.DTMFchar2code(out_buf[i]);
// start transmitting
radio.setDTMFCode(code); // set first
radio.setTxSourceTones();
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute during transmit
radio.setUnmute();
radio.setModeTransmit();
delay(300); // wait for TX to come to full power
bool dtmf_to_tx = true;
while (dtmf_to_tx) {
// wait until ready
while (radio.getDTMFTxActive() != 1) {
// wait until we're ready for a new code
delay(10);
}
if (i < 32 && out_buf[i] != ';' && out_buf[i] != 0) {
code = radio.DTMFchar2code(out_buf[i]);
if (code == 255) code = 0xE; // throw a * in there so we don't break things with an invalid code
radio.setDTMFCode(code); // set first
} else {
dtmf_to_tx = false;
break;
}
i++;
while (radio.getDTMFTxActive() != 0) {
// wait until this code is done
delay(10);
}
}
// done with tone
radio.setModeReceive();
if (repeater == true) {radio.frequency(freq);}
radio.setTxSourceMic();
}
void dtmf_rx() {
char m = radio.DTMFRxLoop();
if (m != 0) {
// Note: not doing buffering of messages,
// we just send a single morse character
// whenever we get it
Serial.print('R');
Serial.print(m);
Serial.println(';');
}
}
// TODO: morse config info
void morse_rx_setup() {
// Set the morse code characteristics
radio.setMorseFreq(MORSE_FREQ);
radio.setMorseDotMillis(MORSE_DOT);
radio.lookForTone(MORSE_FREQ);
radio.setupMorseRx();
}
void morse_rx() {
char m = radio.morseRxLoop();
if (m != 0) {
// Note: not doing buffering of messages,
// we just send a single morse character
// whenever we get it
Serial.print('R');
Serial.print(m);
Serial.println(';');
}
}
void pl_tone_tx() {
memset(pl_tx_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
if(buf == 'X') { return; }
if(buf == ';') { pl_tx_buffer[ptr] = 0; program_pl_tx(); return; }
if(ptr == 31) { return; }
pl_tx_buffer[ptr] = buf; ptr++;
}
}
}
void program_pl_tx() {
float pl_tx = atof(pl_tx_buffer);
radio.setCtcss(pl_tx);
if (pl_tx == 0) {
radio.disableCtcssTx();
} else {
radio.enableCtcssTx();
}
}
void pl_tone_rx() {
memset(pl_rx_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
if(buf == 'X') { return; }
if(buf == ';') { pl_rx_buffer[ptr] = 0; program_pl_rx(); return; }
if(ptr == 31) { return; }
pl_rx_buffer[ptr] = buf; ptr++;
}
}
}
void program_pl_rx() {
float pl_rx = atof(pl_rx_buffer);
radio.setCtcss(pl_rx);
if (pl_rx == 0) {
rx_ctcss = false;
radio.setUnmute();
muted = false;
radio.disableCtcssRx();
} else {
rx_ctcss = true;
radio.setMute();
muted = true;
radio.enableCtcssRx();
}
}
/*
SerialTransceiver is TTL Serial port "glue" to allow desktop or laptop control of the HamShield
Commands:
Mode ASCII Description Implemented
-------------- ----------- -------------------------------------------------------------------------------------------------------------------------------------------- -----------------
Transmit space Space must be received at least every 500 mS Yes
Receive not space If space is not received and/or 500 mS timeout of space occurs, unit will go into receive mode Yes
CTCSS In A<tone>; <tone> must be a numerical ascii value with decimal point indicating CTCSS receive tone required to unsquelch No
CTCSS Out B<tone>; <tone> must be a numerical ascii value with decimal point indicating CTCSS transmit tone No
CTCSS Enable C<state>; Turns on CTCSS mode (analog tone) with 1, off with 0. No
CDCSS Enable D<state>; Turns on CDCSS mode (digital tone) with 1, off with 0. No
Bandwidth E<mode>; for 12.5KHz mode is 0, for 25KHz, mode is 1 No
Frequency F<freq>; Set the receive frequency in KHz, if offset is disabled, this is the transmit frequency No
CDCSS In G<code>; <code> must be a valid CDCSS code No
CDCSS Out H<code>; <code> must be a valid CDCSS code No
Print tones I Prints out all configured tones and codes, coma delimited in format: CTCSS In, CTCSS Out, CDCSS In, CDCSS Out No
Morse Out M<text>; A small buffer for morse code (32 chars)
Power level P<level>; Set the power amp level, 0 = lowest, 15 = highest No
Enable Offset R<state>; 1 turns on repeater offset mode, 0 turns off repeater offset mode No
Squelch S<level>; Set the squelch level No
TX Offset T<freq>; The absolute frequency of the repeater offset to transmit on in KHz No
Volume V<level>; Set the volume level of the receiver No
Reset X Reset all settings to default No
Sleep Z Sleep radio No
Filters @<state>; Set bit to enable, clear bit to disable: 0 = pre/de-emphasis, 1 = high pass filter, 2 = low pass filter (default: ascii 7, all enabled) No
Vox mode $<state>; 0 = vox off, >= 1 audio sensitivity. lower value more sensitive No
Mic Channel *<state>; Set the voice channel. 0 = signal from mic or arduino, 1 = internal tone generator No
RSSI ? Respond with the current receive level in - dBm (no sign provided on numerical response) No
Tone Gen % (notes) To send a tone, use the following format: Single tone: %1,<freq>,<length>; Dual tone: %2,<freq>,<freq>,<length>; DTMF: %3,<key>,<length>; No
Voice Level ^ Respond with the current voice level (VSSI)
Responses:
Condition ASCII Description
------------ ---------- -----------------------------------------------------------------
Startup *<code>; Startup and shield connection status
Success !; Generic success message for command that returns no value
Error X<code>; Indicates an error code. The numerical value is the type of error
Value :<value>; In response to a query
Status #<value>; Unsolicited status message
Debug Msg @<text>; 32 character debug message
*/
#include "HamShield.h"
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
int state;
int txcount = 0;
long timer = 0;
long freq = 144390;
long tx = 0;
char cmdbuff[32] = "";
int temp = 0;
int repeater = 0;
float ctcssin = 0;
float ctcssout = 0;
int cdcssin = 0;
int cdcssout = 0;
HamShield radio;
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
Serial.begin(115200);
Serial.print(";;;;;;;;;;;;;;;;;;;;;;;;;;");
int result = radio.testConnection();
Serial.print("*");
Serial.print(result,DEC);
Serial.print(";");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.print("*START;");
radio.frequency(freq);
radio.setVolume1(0xF);
radio.setVolume2(0xF);
radio.setModeReceive();
radio.setTxSourceMic();
radio.setRfPower(0);
radio.setSQLoThresh(80);
radio.setSQOn();
}
void loop() {
if(Serial.available()) {
int text = Serial.read();
switch (state) {
case 10:
if(text == 32) { timer = millis();}
break;
case 0:
switch(text) {
case 32: // space - transmit
if(repeater == 1) { radio.frequency(tx); }
radio.setModeTransmit();
state = 10;
Serial.print("#TX,ON;");
timer = millis();
break;
case 63: // ? - RSSI
Serial.print(":");
Serial.print(radio.readRSSI(),DEC);
Serial.print(";");
break;
case 65: // A - CTCSS In
getValue();
ctcssin = atof(cmdbuff);
radio.setCtcss(ctcssin);
break;
case 66: // B - CTCSS Out
break;
case 67: // C - CTCSS Enable
break;
case 68: // D - CDCSS Enable
break;
case 70: // F - frequency
getValue();
freq = atol(cmdbuff);
if(radio.frequency(freq) == true) { Serial.print("@"); Serial.print(freq,DEC); Serial.print(";!;"); } else { Serial.print("X1;"); }
break;
case 'M':
getValue();
radio.setModeTransmit();
delay(300);
radio.morseOut(cmdbuff);
state = 10;
break;
case 80: // P - power level
getValue();
temp = atol(cmdbuff);
radio.setRfPower(temp);
break;
case 82: // R - repeater offset mode
getValue();
temp = atol(cmdbuff);
if(temp == 0) { repeater = 0; }
if(temp == 1) { repeater = 1; }
break;
case 83: // S - squelch
getValue();
temp = atol(cmdbuff);
radio.setSQLoThresh(temp);
break;
case 84: // T - transmit offset
getValue();
tx = atol(cmdbuff);
break;
case 94: // ^ - VSSI (voice) level
Serial.print(":");
Serial.print(radio.readVSSI(),DEC);
Serial.print(";");
}
break;
}
}
if(state == 10) {
if(millis() > (timer + 500)) { Serial.print("#TX,OFF;");radio.setModeReceive(); if(repeater == 1) { radio.frequency(freq); } state = 0; txcount = 0; }
}
}
void getValue() {
int p = 0;
char temp;
for(;;) {
if(Serial.available()) {
temp = Serial.read();
if(temp == 59) { cmdbuff[p] = 0; Serial.print("@");
for(int x = 0; x < 32; x++) { Serial.print(cmdbuff[x]); }
return;
}
cmdbuff[p] = temp;
p++;
if(p == 32) {
Serial.print("@");
for(int x = 0; x < 32; x++) {
Serial.print(cmdbuff[x]);
}
cmdbuff[0] = 0;
Serial.print("X0;"); return; } // some sort of alignment issue? lets not feed junk into whatever takes this string in
}
}
}

View File

@ -1,704 +0,0 @@
/* Hamshield
* Example: AppSerialController_nRF52840
* This is a simple example to demonstrate the HamShield working
* with an Adafruit Feather nRF52840 Express
*
* HamShield to Feather Connections:
* SPKR - Feather A0
* MIC - Feather D11
* CLK - Feather D5
* nCS - Feather D6
* DAT - Feather D9
* GND - Feather GND
* VCC - Feather 3.3V
*
* Connect the HamShield to your Feather as above.
* Screw the antenna into the HamShield RF jack. Plug a pair
* of headphones into the HamShield.
*
* Connect the Feather nRF52840 Express to your computer via
* a USB Micro B cable. After uploading this program to
* your Feather, open the Serial Monitor. You should see some
* text displayed that documents the setup process.
*
* Once the Feather is set up and talking to the HamShield,
* you can control it over USB-Serial or BLE-Serial(UART).
*
* Try using Adafruit's Bluefruit app to connect to the Feather.
* Once you're connected, you can control the HamShield using
* the same commands you'd use over USB-Serial. The response to
* all commands will be echoed to both USB-Serial and BLE-Serial(UART).
*
Commands:
Mode ASCII Description
-------------- ----------- --------------------------------------------------------------------------------------------------------------------------------------------
Transmit space Space must be received at least every 500 mS
Receive not space If space is not received and/or 500 mS timeout of space occurs, unit will go into receive mode
Frequency F<freq>; Set the receive frequency in KHz, if offset is disabled, this is the transmit frequency
Morse Out M<text>; A small buffer for morse code (32 chars)
Morse In N; Sets mode to Morse In, listening for Morse
Power level P<level>; Set the power amp level, 0 = lowest, 15 = highest
Enable Offset R<state>; 1 turns on repeater offset mode, 0 turns off repeater offset mode
Squelch S<level>; Set the squelch level
TX Offset T<freq>; The absolute frequency of the repeater offset to transmit on in KHz
RSSI ? Respond with the current receive level in - dBm (no sign provided on numerical response)
Voice Level ^ Respond with the current voice level (VSSI), only valid when transmitting
DTMF Out D<vals>; A small buffer for DTMF out (only 0-9,A,B,C,D,*,# accepted)
DTMF In B; Sets mode to DTMF In, listening for DTMF
PL Tone Tx A<val>; Sets PL tone for TX, value is tone frequency in Hz (float), set to 0 to disable
PL Tone Rx C<val>; Sets PL tone for RX, value is tone frequency in Hz (float), set to 0 to disable
Volume 1 V1<val>; Set volume 1 (value between 0 and 15)
Volume 2 V2<val>; Set volume 2 (value between 0 and 15)
KISS TNC K; Move to KISS TNC mode (send ^; to move back to normal mode). NOT IMPELEMENTED YET
Normal Mode _ Move to Normal mode from any other mode (except TX)
Responses:
Condition ASCII Description
------------ ---------- -----------------------------------------------------------------
Startup *<code>; Startup and shield connection status
Success !; Generic success message for command that returns no value
Error X<code>; Indicates an error code. The numerical value is the type of error
Value :<value>; In response to a query
Status #<value>; Unsolicited status message
Debug Msg @<text>; 32 character debug message
Rx Msg R<text>; up to 32 characters of received message, only if device is in DTMF or Morse Rx modes
*/
// Note that the following are not yet implemented
// TODO: change get_value so it's intuitive
// TODO: Squelch open and squelch shut independently controllable
// TODO: pre/de emph filter
// TODO: walkie-talkie
// TODO: KISS TNC
#include <bluefruit.h>
#include <stdarg.h>
#include <stdio.h>
#include <HamShield.h>
// BLE Service
BLEDis bledis; // device information
BLEUart bleuart; // uart over ble
BLEBas blebas; // battery
// create object for radio
HamShield radio(6,5,9);
// To use non-standard pins, use the following initialization
//HamShield radio(ncs_pin, clk_pin, dat_pin);
#define LED_PIN 3
#define MIC_PIN A1
enum {TX, NORMAL, DTMF, MORSE, KISS};
int state = NORMAL;
bool rx_ctcss = false;
bool muted = false;
int txcount = 0;
long timer = 0; // Transmit timer to track timeout (send space to reset)
long freq = 432100; // 70cm calling frequency, receive frequency and default transmit frequency
long tx_freq = 0; // transmit frequency if repeater is on
int pwr = 0; // tx power
char cmdbuff[32] = "";
int temp = 0;
bool repeater = false; // true if transmit and receive operate on different frequencies
char pl_rx_buffer[32]; // pl tone rx buffer
char pl_tx_buffer[32]; // pl tone tx buffer
float ctcssin = 0;
float ctcssout = 0;
int cdcssin = 0;
int cdcssout = 0;
void setup() {
// NOTE: if not using PWM out (MIC pin), it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
// initialize serial communication
Serial.begin(115200);
while (!Serial) delay(10);
// Setup the BLE LED to be enabled on CONNECT
// Note: This is actually the default behaviour, but provided
// here in case you want to control this LED manually via PIN 19
Bluefruit.autoConnLed(true);
// Config the peripheral connection with maximum bandwidth
// more SRAM required by SoftDevice
// Note: All config***() function must be called before begin()
Bluefruit.configPrphBandwidth(BANDWIDTH_MAX);
Bluefruit.begin();
// Set max power. Accepted values are: -40, -30, -20, -16, -12, -8, -4, 0, 4
Bluefruit.setTxPower(4);
Bluefruit.setName("MyBlueHam");
//Bluefruit.setName(getMcuUniqueID()); // useful testing with multiple central connections
Bluefruit.setConnectCallback(connect_callback);
Bluefruit.setDisconnectCallback(disconnect_callback);
// Configure and Start Device Information Service
bledis.setManufacturer("Enhanced Radio Devices");
bledis.setModel("BlueHam");
bledis.begin();
// Configure and Start BLE Uart Service
bleuart.begin();
// Start BLE Battery Service
blebas.begin();
blebas.write(100);
// Set up and start advertising
startAdv();
delay(100);
SerialWrite(";;;;;;;;;;;;;;;;;;;;;;;;;;\n");
int result = radio.testConnection();
SerialWrite("*%d;\n", result);
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
radio.frequency(freq);
radio.setVolume1(0xF);
radio.setVolume2(0xF);
radio.setModeReceive();
radio.setTxSourceMic();
radio.setRfPower(pwr);
radio.setSQLoThresh(-80);
radio.setSQHiThresh(-70);
radio.setSQOn();
SerialWrite("*START;\n");
}
void startAdv(void)
{
// Advertising packet
Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE);
Bluefruit.Advertising.addTxPower();
// Include bleuart 128-bit uuid
Bluefruit.Advertising.addService(bleuart);
// Secondary Scan Response packet (optional)
// Since there is no room for 'Name' in Advertising packet
Bluefruit.ScanResponse.addName();
/* Start Advertising
* - Enable auto advertising if disconnected
* - Interval: fast mode = 20 ms, slow mode = 152.5 ms
* - Timeout for fast mode is 30 seconds
* - Start(timeout) with timeout = 0 will advertise forever (until connected)
*
* For recommended advertising interval
* https://developer.apple.com/library/content/qa/qa1931/_index.html
*/
Bluefruit.Advertising.restartOnDisconnect(true);
Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms
Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode
Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds
}
void loop() {
// TODO: loop fixing based on serialtransciever!
char c = 0;
bool ble_serial = false;
if (Serial.available()) {
Serial.readBytes(&c, 1);
} else if (bleuart.available()) {
c = (char) bleuart.read();
ble_serial = true;
}
// TODO: BLE
if(c != 0) {
int text = c; // get the first char to see what the upcoming command is
switch (state) {
// we handle commands differently based on what state we're in
case TX:
// we're currently transmitting
// if we got a space, reset our transmit timeout
if(text == ' ') { timer = millis();}
break;
case NORMAL:
switch(text) {
case ' ': // space - transmit
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute (for PL tones) during tx
radio.setUnmute();
radio.setModeTransmit();
state = TX;
SerialWrite("#TX,ON;\n");
timer = millis();
break;
case '?': // ? - RSSI
SerialWrite(":%d;\n", radio.readRSSI());
break;
case '^': // ^ - VSSI (voice) level
SerialWrite(":%d;\n", radio.readVSSI());
break;
case 'F': // F - frequency
getValue(ble_serial);
freq = atol(cmdbuff);
if(radio.frequency(freq) == true) {
SerialWrite("@%d;!;\n", freq);
} else {
SerialWrite("X1;\n");
}
break;
case 'P': // P - power level
getValue(ble_serial);
temp = atol(cmdbuff);
radio.setRfPower(temp);
SerialWrite("!;\n");
break;
case 'S': // S - squelch
getValue(ble_serial);
temp = atol(cmdbuff);
if (temp < -2 && temp > -130) {
radio.setSQLoThresh(temp);
radio.setSQHiThresh(temp+2);
radio.setSQOn();
SerialWrite("%d!;\n", temp);
} else {
SerialWrite("X!;\n");
}
break;
case 'R': // R - repeater offset mode
getValue(ble_serial);
temp = atol(cmdbuff);
if(temp == 0) { repeater = 0; }
if(temp == 1) { repeater = 1; }
SerialWrite("!;\n");
break;
case 'T': // T - transmit offset
getValue(ble_serial);
tx_freq = atol(cmdbuff);
SerialWrite("!;\n");
break;
case 'M': // M - Morse
getValue(ble_serial);
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute (for PL tones) during tx
radio.setUnmute();
radio.setModeTransmit();
delay(300);
radio.morseOut(cmdbuff);
if(repeater == true) { radio.frequency(freq); }
radio.setModeReceive();
SerialWrite("!;\n");
break;
case 'N': // N - set to Morse in Mode
morse_rx_setup();
state = MORSE;
SerialWrite("!;\n");
break;
case 'D': // D - DTMF Out
dtmfSetup();
getValue(ble_serial);
dtmf_out(cmdbuff);
SerialWrite("!;\n");
break;
case 'B': // B - set to DTMF in Mode
dtmfSetup();
radio.enableDTMFReceive();
state = DTMF;
SerialWrite("!;\n");
break;
case 'A': // A - TX PL Tone configuration command
pl_tone_tx();
SerialWrite("!;\n");
break;
case 'C': // C - RX PL Tone configuration command
pl_tone_rx();
SerialWrite("!;\n");
break;
case 'V': // V - set volume
getValue(ble_serial);
temp = cmdbuff[0];
if (temp == 0x31) {
temp = atol(cmdbuff + 1);
radio.setVolume1(temp);
SerialWrite("!;\n");
} else if (temp == 0x32) {
temp = atol(cmdbuff + 1);
radio.setVolume2(temp);
SerialWrite("!;\n");
} else {
// not a valid volume command, flush buffers
SerialFlush(ble_serial);
SerialWrite("X!;\n");
}
break;
case 'K': // K - switch to KISS TNC mode
//state = KISS;
//TODO: set up KISS
SerialWrite("X1;\n");
break;
default:
// unknown command, flush the input buffer and wait for next one
SerialWrite("X1;\n");
SerialFlush(ble_serial);
break;
}
break;
case KISS:
if ((ble_serial && bleuart.peek() == '_') || (!ble_serial && Serial.peek() == '_')) {
state = NORMAL;
if (rx_ctcss) {
radio.enableCtcss();
muted = true; // can't mute (for PL tones) during tx
radio.setMute();
}
}
// TODO: handle KISS TNC
break;
case MORSE:
if (text == '_') { state = NORMAL; }
if (text == 'M') { // tx message
getValue(ble_serial);
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute (for PL tones) during tx
radio.setUnmute();
radio.setModeTransmit();
delay(300);
radio.morseOut(cmdbuff);
if(repeater == true) { radio.frequency(freq); }
radio.setModeReceive();
} else {
// not a valid cmd
SerialFlush(ble_serial);
}
break;
case DTMF:
if (text == '_') { state = NORMAL; }
if (text == 'D') { // tx message
getValue(ble_serial);
dtmf_out(cmdbuff);
} else {
// not a valid cmd
SerialFlush(ble_serial);
}
break;
default:
// we're in an invalid state, reset to safe settings
SerialFlush(ble_serial);
radio.frequency(freq);
radio.setModeReceive();
state = NORMAL;
break;
}
}
// now handle any state related functions
switch (state) {
case TX:
if(millis() > (timer + 500)) {
SerialWrite("#TX,OFF;\n");
radio.setModeReceive();
if(repeater == true) { radio.frequency(freq); }
if (rx_ctcss) {
radio.setMute();
muted = true;
}
txcount = 0;
state = NORMAL;
}
break;
case NORMAL:
// deal with rx ctccs if necessary
if (rx_ctcss) {
if (radio.getCtcssToneDetected()) {
if (muted) {
muted = false;
radio.setUnmute();
}
} else {
if (!muted) {
muted = true;
radio.setMute();
}
}
}
break;
case DTMF:
dtmf_rx(); // wait for DTMF reception
break;
case MORSE:
morse_rx(); // wait for Morse reception
break;
}
// get rid of any trailing whitespace in the serial buffer
SerialFlushWhitespace(ble_serial);
}
// callback invoked when central connects
void connect_callback(uint16_t conn_handle)
{
char central_name[32] = { 0 };
Bluefruit.Gap.getPeerName(conn_handle, central_name, sizeof(central_name));
Serial.print("Connected to ");
Serial.println(central_name);
}
/**
* Callback invoked when a connection is dropped
* @param conn_handle connection where this event happens
* @param reason is a BLE_HCI_STATUS_CODE which can be found in ble_hci.h
* https://github.com/adafruit/Adafruit_nRF52_Arduino/blob/master/cores/nRF5/nordic/softdevice/s140_nrf52_6.1.1_API/include/ble_hci.h
*/
void disconnect_callback(uint16_t conn_handle, uint8_t reason)
{
(void) conn_handle;
(void) reason;
Serial.println();
Serial.println("Disconnected");
}
void getValue(bool ble_serial) {
int p = 0;
char temp;
for(;;) {
if((!ble_serial && Serial.available()) || (ble_serial && bleuart.available())) {
if (ble_serial) {
temp = bleuart.read();
} else {
temp = Serial.read();
}
if(temp == 59) {
cmdbuff[p] = 0;
return;
}
cmdbuff[p] = temp;
p++;
if(p == 32) {
cmdbuff[0] = 0;
return;
}
}
}
}
void dtmfSetup() {
radio.setVolume1(6);
radio.setVolume2(0);
radio.setDTMFDetectTime(24); // time to detect a DTMF code, units are 2.5ms
radio.setDTMFIdleTime(50); // time between transmitted DTMF codes, units are 2.5ms
radio.setDTMFTxTime(60); // duration of transmitted DTMF codes, units are 2.5ms
}
void dtmf_out(char * out_buf) {
if (out_buf[0] == ';' || out_buf[0] == 0) return; // empty message
uint8_t i = 0;
uint8_t code = radio.DTMFchar2code(out_buf[i]);
// start transmitting
radio.setDTMFCode(code); // set first
radio.setTxSourceTones();
if(repeater == true && tx_freq != 0) { radio.frequency(tx_freq); }
muted = false; // can't mute during transmit
radio.setUnmute();
radio.setModeTransmit();
delay(300); // wait for TX to come to full power
bool dtmf_to_tx = true;
while (dtmf_to_tx) {
// wait until ready
while (radio.getDTMFTxActive() != 1) {
// wait until we're ready for a new code
delay(10);
}
if (i < 32 && out_buf[i] != ';' && out_buf[i] != 0) {
code = radio.DTMFchar2code(out_buf[i]);
if (code == 255) code = 0xE; // throw a * in there so we don't break things with an invalid code
radio.setDTMFCode(code); // set first
} else {
dtmf_to_tx = false;
break;
}
i++;
while (radio.getDTMFTxActive() != 0) {
// wait until this code is done
delay(10);
}
}
// done with tone
radio.setModeReceive();
if (repeater == true) {radio.frequency(freq);}
radio.setTxSourceMic();
}
void dtmf_rx() {
char m = radio.DTMFRxLoop();
if (m != 0) {
// Note: not doing buffering of messages,
// we just send a single morse character
// whenever we get it
SerialWrite("R%d;\n", m);
}
}
// TODO: morse config info
void morse_rx_setup() {
// Set the morse code characteristics
radio.setMorseFreq(MORSE_FREQ);
radio.setMorseDotMillis(MORSE_DOT);
radio.lookForTone(MORSE_FREQ);
radio.setupMorseRx();
}
void morse_rx() {
char m = radio.morseRxLoop();
if (m != 0) {
// Note: not doing buffering of messages,
// we just send a single morse character
// whenever we get it
SerialWrite("R%c;\n",m);
}
}
void pl_tone_tx() {
memset(pl_tx_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
if(buf == 'X') { return; }
if(buf == ';') { pl_tx_buffer[ptr] = 0; program_pl_tx(); return; }
if(ptr == 31) { return; }
pl_tx_buffer[ptr] = buf; ptr++;
}
}
}
void program_pl_tx() {
float pl_tx = atof(pl_tx_buffer);
radio.setCtcss(pl_tx);
if (pl_tx == 0) {
radio.disableCtcssTx();
} else {
radio.enableCtcssTx();
}
}
void pl_tone_rx() {
memset(pl_rx_buffer,0,32);
uint8_t ptr = 0;
while(1) {
if(Serial.available()) {
uint8_t buf = Serial.read();
if(buf == 'X') { return; }
if(buf == ';') { pl_rx_buffer[ptr] = 0; program_pl_rx(); return; }
if(ptr == 31) { return; }
pl_rx_buffer[ptr] = buf; ptr++;
}
}
}
void program_pl_rx() {
float pl_rx = atof(pl_rx_buffer);
radio.setCtcss(pl_rx);
if (pl_rx == 0) {
rx_ctcss = false;
radio.setUnmute();
muted = false;
radio.disableCtcssRx();
} else {
rx_ctcss = true;
radio.setMute();
muted = true;
radio.enableCtcssRx();
}
}
#define TEXT_BUF_LEN 64
char text_buf[TEXT_BUF_LEN];
void SerialWrite(const char *fmt, ...) {
va_list args;
va_start(args, fmt);
int str_len = vsnprintf(text_buf, TEXT_BUF_LEN, fmt, args);
va_end(args);
bleuart.write(text_buf, str_len);
Serial.write(text_buf, str_len);
}
void SerialFlush(bool ble_serial) {
if (ble_serial) {
while (bleuart.available()) { bleuart.read(); }
} else {
while (Serial.available()) { Serial.read(); }
}
}
void SerialFlushWhitespace(bool ble_serial) {
if (!ble_serial && Serial.available()) {
char cpeek = Serial.peek();
while (cpeek == ' ' || cpeek == '\r' || cpeek == '\n')
{
Serial.read();
cpeek = Serial.peek();
}
} else if (ble_serial && bleuart.available()) {
char cpeek = bleuart.peek();
while (cpeek == ' ' || cpeek == '\r' || cpeek == '\n')
{
bleuart.read();
cpeek = bleuart.peek();
}
}
}

View File

@ -1,31 +1,19 @@
/* Hamshield
* Example: Signal Test
* Transmits current signal strength level and Morses out
* it's call sign at the end. You will need a HandyTalkie (HT)
* to test the output of this example. You will also need to
* download the PCM library from
* https://github.com/damellis/PCM
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Plug a pair of headphones into
* the HamShield. Connect the Arduino to wall power and then
* to your computer via USB. After uploading this program to
* your Arduino, open the Serial Monitor. HamShield will print
* the results of its signal test to the Serial Monitor. To
* test with another HandyTalkie (HT), tune in to 446MHz and
* listen for the call sign. Then key up on your HT and make
* sure you can hear it through the headphones attached to the
* HamShield.
*/
/*
Plays back the current signal strength level and morses out it's call sign at the end.
*/
#define DOT 100
char CALLSIGN[] = "1ZZ9ZZ/B";
#define CALLSIGN "1ZZ9ZZ/B"
/* Standard libraries and variable init */
#include <HamShield.h>
#include <PCM.h>
#define MIC_PIN 3
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
@ -90,24 +78,22 @@ const unsigned char dbm[] PROGMEM = {
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW);
pinMode(PWM_PIN, OUTPUT);
digitalWrite(PWM_PIN, LOW);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.begin(9600);
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result);
radio.initialize();
radio.frequency(432400);
radio.frequency(446000);
radio.setVolume1(0xF);
radio.setVolume2(0xF);
radio.setModeReceive();

View File

@ -1,284 +0,0 @@
/* Hamshield (See https://github.com/EnhancedRadioDevices/HamShield)
* Example: SpeechTX - This example used the basic JustTransmit example from the above site
* This example uses the Talkie Arduino speech library. It transmits pre-encoded speech over the air.
* More info at: https://github.com/going-digital/Talkie
*
* Make sure you're using an Arduino Uno or equivalent. The Talkie library doesn't work
* with hardware that doesn't use the ATMega328 or ATMega168.
*
* Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to
* wall power and then to your computer via USB. After
* uploading this program to your Arduino
* tune a HandyTalkie (HT) to 144.025MHz. Listen on
* the HT for the HamShield broadcasting with its own speech.
*/
#include <HamShield.h>
#define MIC_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
#include "talkie.h"
Talkie voice;
const uint8_t spZERO[] PROGMEM = {0x69,0xFB,0x59,0xDD,0x51,0xD5,0xD7,0xB5,0x6F,0x0A,0x78,0xC0,0x52,0x01,0x0F,0x50,0xAC,0xF6,0xA8,0x16,0x15,0xF2,0x7B,0xEA,0x19,0x47,0xD0,0x64,0xEB,0xAD,0x76,0xB5,0xEB,0xD1,0x96,0x24,0x6E,0x62,0x6D,0x5B,0x1F,0x0A,0xA7,0xB9,0xC5,0xAB,0xFD,0x1A,0x62,0xF0,0xF0,0xE2,0x6C,0x73,0x1C,0x73,0x52,0x1D,0x19,0x94,0x6F,0xCE,0x7D,0xED,0x6B,0xD9,0x82,0xDC,0x48,0xC7,0x2E,0x71,0x8B,0xBB,0xDF,0xFF,0x1F};
const uint8_t spFOUR[] PROGMEM = {0x08,0x68,0x21,0x0D,0x03,0x04,0x28,0xCE,0x92,0x03,0x23,0x4A,0xCA,0xA6,0x1C,0xDA,0xAD,0xB4,0x70,0xED,0x19,0x64,0xB7,0xD3,0x91,0x45,0x51,0x35,0x89,0xEA,0x66,0xDE,0xEA,0xE0,0xAB,0xD3,0x29,0x4F,0x1F,0xFA,0x52,0xF6,0x90,0x52,0x3B,0x25,0x7F,0xDD,0xCB,0x9D,0x72,0x72,0x8C,0x79,0xCB,0x6F,0xFA,0xD2,0x10,0x9E,0xB4,0x2C,0xE1,0x4F,0x25,0x70,0x3A,0xDC,0xBA,0x2F,0x6F,0xC1,0x75,0xCB,0xF2,0xFF};
const uint8_t spEIGHT[] PROGMEM = {0x65,0x69,0x89,0xC5,0x73,0x66,0xDF,0xE9,0x8C,0x33,0x0E,0x41,0xC6,0xEA,0x5B,0xEF,0x7A,0xF5,0x33,0x25,0x50,0xE5,0xEA,0x39,0xD7,0xC5,0x6E,0x08,0x14,0xC1,0xDD,0x45,0x64,0x03,0x00,0x80,0x00,0xAE,0x70,0x33,0xC0,0x73,0x33,0x1A,0x10,0x40,0x8F,0x2B,0x14,0xF8,0x7F};
const uint8_t spTWELVE[] PROGMEM = {0x09,0x98,0xDA,0x22,0x01,0x37,0x78,0x1A,0x20,0x85,0xD1,0x50,0x3A,0x33,0x11,0x81,0x5D,0x5B,0x95,0xD4,0x44,0x04,0x76,0x9D,0xD5,0xA9,0x3A,0xAB,0xF0,0xA1,0x3E,0xB7,0xBA,0xD5,0xA9,0x2B,0xEB,0xCC,0xA0,0x3E,0xB7,0xBD,0xC3,0x5A,0x3B,0xC8,0x69,0x67,0xBD,0xFB,0xE8,0x67,0xBF,0xCA,0x9D,0xE9,0x74,0x08,0xE7,0xCE,0x77,0x78,0x06,0x89,0x32,0x57,0xD6,0xF1,0xF1,0x8F,0x7D,0xFE,0x1F};
const uint8_t spTWENTY[] PROGMEM = {0x0A,0xE8,0x4A,0xCD,0x01,0xDB,0xB9,0x33,0xC0,0xA6,0x54,0x0C,0xA4,0x34,0xD9,0xF2,0x0A,0x6C,0xBB,0xB3,0x53,0x0E,0x5D,0xA6,0x25,0x9B,0x6F,0x75,0xCA,0x61,0x52,0xDC,0x74,0x49,0xA9,0x8A,0xC4,0x76,0x4D,0xD7,0xB1,0x76,0xC0,0x55,0xA6,0x65,0xD8,0x26,0x99,0x5C,0x56,0xAD,0xB9,0x25,0x23,0xD5,0x7C,0x32,0x96,0xE9,0x9B,0x20,0x7D,0xCB,0x3C,0xFA,0x55,0xAE,0x99,0x1A,0x30,0xFC,0x4B,0x3C,0xFF,0x1F};
const uint8_t spONE[] PROGMEM = {0x66,0x4E,0xA8,0x7A,0x8D,0xED,0xC4,0xB5,0xCD,0x89,0xD4,0xBC,0xA2,0xDB,0xD1,0x27,0xBE,0x33,0x4C,0xD9,0x4F,0x9B,0x4D,0x57,0x8A,0x76,0xBE,0xF5,0xA9,0xAA,0x2E,0x4F,0xD5,0xCD,0xB7,0xD9,0x43,0x5B,0x87,0x13,0x4C,0x0D,0xA7,0x75,0xAB,0x7B,0x3E,0xE3,0x19,0x6F,0x7F,0xA7,0xA7,0xF9,0xD0,0x30,0x5B,0x1D,0x9E,0x9A,0x34,0x44,0xBC,0xB6,0x7D,0xFE,0x1F};
const uint8_t spFIVE[] PROGMEM = {0x08,0x68,0x4E,0x9D,0x02,0x1C,0x60,0xC0,0x8C,0x69,0x12,0xB0,0xC0,0x28,0xAB,0x8C,0x9C,0xC0,0x2D,0xBB,0x38,0x79,0x31,0x15,0xA3,0xB6,0xE4,0x16,0xB7,0xDC,0xF5,0x6E,0x57,0xDF,0x54,0x5B,0x85,0xBE,0xD9,0xE3,0x5C,0xC6,0xD6,0x6D,0xB1,0xA5,0xBF,0x99,0x5B,0x3B,0x5A,0x30,0x09,0xAF,0x2F,0xED,0xEC,0x31,0xC4,0x5C,0xBE,0xD6,0x33,0xDD,0xAD,0x88,0x87,0xE2,0xD2,0xF2,0xF4,0xE0,0x16,0x2A,0xB2,0xE3,0x63,0x1F,0xF9,0xF0,0xE7,0xFF,0x01};
const uint8_t spNINE[] PROGMEM = {0xE6,0xA8,0x1A,0x35,0x5D,0xD6,0x9A,0x35,0x4B,0x8C,0x4E,0x6B,0x1A,0xD6,0xA6,0x51,0xB2,0xB5,0xEE,0x58,0x9A,0x13,0x4F,0xB5,0x35,0x67,0x68,0x26,0x3D,0x4D,0x97,0x9C,0xBE,0xC9,0x75,0x2F,0x6D,0x7B,0xBB,0x5B,0xDF,0xFA,0x36,0xA7,0xEF,0xBA,0x25,0xDA,0x16,0xDF,0x69,0xAC,0x23,0x05,0x45,0xF9,0xAC,0xB9,0x8F,0xA3,0x97,0x20,0x73,0x9F,0x54,0xCE,0x1E,0x45,0xC2,0xA2,0x4E,0x3E,0xD3,0xD5,0x3D,0xB1,0x79,0x24,0x0D,0xD7,0x48,0x4C,0x6E,0xE1,0x2C,0xDE,0xFF,0x0F};
const uint8_t spTHIR_[] PROGMEM = {0x04,0xA8,0xBE,0x5C,0x00,0xDD,0xA5,0x11,0xA0,0xFA,0x72,0x02,0x74,0x97,0xC6,0x01,0x09,0x9C,0xA6,0xAB,0x30,0x0D,0xCE,0x7A,0xEA,0x6A,0x4A,0x39,0x35,0xFB,0xAA,0x8B,0x1B,0xC6,0x76,0xF7,0xAB,0x2E,0x79,0x19,0xCA,0xD5,0xEF,0xCA,0x57,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x00,0xC0,0xFF,0x03};
const uint8_t spHUNDRED[] PROGMEM = {0x04,0xC8,0x7E,0x5C,0x02,0x0A,0xA8,0x62,0x43,0x03,0xA7,0xA8,0x62,0x43,0x4B,0x97,0xDC,0xF2,0x14,0xC5,0xA7,0x9B,0x7A,0xD3,0x95,0x37,0xC3,0x1E,0x16,0x4A,0x66,0x36,0xF3,0x5A,0x89,0x6E,0xD4,0x30,0x55,0xB5,0x32,0xB7,0x31,0xB5,0xC1,0x69,0x2C,0xE9,0xF7,0xBC,0x96,0x12,0x39,0xD4,0xB5,0xFD,0xDA,0x9B,0x0F,0xD1,0x90,0xEE,0xF5,0xE4,0x17,0x02,0x45,0x28,0x77,0x11,0xD9,0x40,0x9E,0x45,0xDD,0x2B,0x33,0x71,0x7A,0xBA,0x0B,0x13,0x95,0x2D,0xF9,0xF9,0x7F};
const uint8_t spTWO[] PROGMEM = {0x06,0xB8,0x59,0x34,0x00,0x27,0xD6,0x38,0x60,0x58,0xD3,0x91,0x55,0x2D,0xAA,0x65,0x9D,0x4F,0xD1,0xB8,0x39,0x17,0x67,0xBF,0xC5,0xAE,0x5A,0x1D,0xB5,0x7A,0x06,0xF6,0xA9,0x7D,0x9D,0xD2,0x6C,0x55,0xA5,0x26,0x75,0xC9,0x9B,0xDF,0xFC,0x6E,0x0E,0x63,0x3A,0x34,0x70,0xAF,0x3E,0xFF,0x1F};
const uint8_t spSIX[] PROGMEM = {0x04,0xF8,0xAD,0x4C,0x02,0x16,0xB0,0x80,0x06,0x56,0x35,0x5D,0xA8,0x2A,0x6D,0xB9,0xCD,0x69,0xBB,0x2B,0x55,0xB5,0x2D,0xB7,0xDB,0xFD,0x9C,0x0D,0xD8,0x32,0x8A,0x7B,0xBC,0x02,0x00,0x03,0x0C,0xB1,0x2E,0x80,0xDF,0xD2,0x35,0x20,0x01,0x0E,0x60,0xE0,0xFF,0x01};
const uint8_t spTEN[] PROGMEM = {0x0E,0x38,0x3C,0x2D,0x00,0x5F,0xB6,0x19,0x60,0xA8,0x90,0x93,0x36,0x2B,0xE2,0x99,0xB3,0x4E,0xD9,0x7D,0x89,0x85,0x2F,0xBE,0xD5,0xAD,0x4F,0x3F,0x64,0xAB,0xA4,0x3E,0xBA,0xD3,0x59,0x9A,0x2E,0x75,0xD5,0x39,0x6D,0x6B,0x0A,0x2D,0x3C,0xEC,0xE5,0xDD,0x1F,0xFE,0xB0,0xE7,0xFF,0x03};
const uint8_t spFIF_[] PROGMEM = {0x08,0x98,0x31,0x93,0x02,0x1C,0xE0,0x80,0x07,0x5A,0xD6,0x1C,0x6B,0x78,0x2E,0xBD,0xE5,0x2D,0x4F,0xDD,0xAD,0xAB,0xAA,0x6D,0xC9,0x23,0x02,0x56,0x4C,0x93,0x00,0x05,0x10,0x90,0x89,0x31,0xFC,0x3F};
const uint8_t spTHOUSAND[] PROGMEM = {0x0C,0xE8,0x2E,0xD4,0x02,0x06,0x98,0xD2,0x55,0x03,0x16,0x68,0x7D,0x17,0xE9,0x6E,0xBC,0x65,0x8C,0x45,0x6D,0xA6,0xE9,0x96,0xDD,0xDE,0xF6,0xB6,0xB7,0x5E,0x75,0xD4,0x93,0xA5,0x9C,0x7B,0x57,0xB3,0x6E,0x7D,0x12,0x19,0xAD,0xDC,0x29,0x8D,0x4F,0x93,0xB4,0x87,0xD2,0xB6,0xFC,0xDD,0xAC,0x22,0x56,0x02,0x70,0x18,0xCA,0x18,0x26,0xB5,0x90,0xD4,0xDE,0x6B,0x29,0xDA,0x2D,0x25,0x17,0x8D,0x79,0x88,0xD4,0x48,0x79,0x5D,0xF7,0x74,0x75,0xA1,0x94,0xA9,0xD1,0xF2,0xED,0x9E,0xAA,0x51,0xA6,0xD4,0x9E,0x7F,0xED,0x6F,0xFE,0x2B,0xD1,0xC7,0x3D,0x89,0xFA,0xB7,0x0D,0x57,0xD3,0xB4,0xF5,0x37,0x55,0x37,0x2E,0xE6,0xB2,0xD7,0x57,0xFF,0x0F};
const uint8_t spTHREE[] PROGMEM = {0x0C,0xE8,0x2E,0x94,0x01,0x4D,0xBA,0x4A,0x40,0x03,0x16,0x68,0x69,0x36,0x1C,0xE9,0xBA,0xB8,0xE5,0x39,0x70,0x72,0x84,0xDB,0x51,0xA4,0xA8,0x4E,0xA3,0xC9,0x77,0xB1,0xCA,0xD6,0x52,0xA8,0x71,0xED,0x2A,0x7B,0x4B,0xA6,0xE0,0x37,0xB7,0x5A,0xDD,0x48,0x8E,0x94,0xF1,0x64,0xCE,0x6D,0x19,0x55,0x91,0xBC,0x6E,0xD7,0xAD,0x1E,0xF5,0xAA,0x77,0x7A,0xC6,0x70,0x22,0xCD,0xC7,0xF9,0x89,0xCF,0xFF,0x03};
const uint8_t spSEVEN[] PROGMEM = {0x0C,0xF8,0x5E,0x4C,0x01,0xBF,0x95,0x7B,0xC0,0x02,0x16,0xB0,0xC0,0xC8,0xBA,0x36,0x4D,0xB7,0x27,0x37,0xBB,0xC5,0x29,0xBA,0x71,0x6D,0xB7,0xB5,0xAB,0xA8,0xCE,0xBD,0xD4,0xDE,0xA6,0xB2,0x5A,0xB1,0x34,0x6A,0x1D,0xA7,0x35,0x37,0xE5,0x5A,0xAE,0x6B,0xEE,0xD2,0xB6,0x26,0x4C,0x37,0xF5,0x4D,0xB9,0x9A,0x34,0x39,0xB7,0xC6,0xE1,0x1E,0x81,0xD8,0xA2,0xEC,0xE6,0xC7,0x7F,0xFE,0xFB,0x7F};
const uint8_t spELEVEN[] PROGMEM = {0xA5,0xEF,0xD6,0x50,0x3B,0x67,0x8F,0xB9,0x3B,0x23,0x49,0x7F,0x33,0x87,0x31,0x0C,0xE9,0x22,0x49,0x7D,0x56,0xDF,0x69,0xAA,0x39,0x6D,0x59,0xDD,0x82,0x56,0x92,0xDA,0xE5,0x74,0x9D,0xA7,0xA6,0xD3,0x9A,0x53,0x37,0x99,0x56,0xA6,0x6F,0x4F,0x59,0x9D,0x7B,0x89,0x2F,0xDD,0xC5,0x28,0xAA,0x15,0x4B,0xA3,0xD6,0xAE,0x8C,0x8A,0xAD,0x54,0x3B,0xA7,0xA9,0x3B,0xB3,0x54,0x5D,0x33,0xE6,0xA6,0x5C,0xCB,0x75,0xCD,0x5E,0xC6,0xDA,0xA4,0xCA,0xB9,0x35,0xAE,0x67,0xB8,0x46,0x40,0xB6,0x28,0xBB,0xF1,0xF6,0xB7,0xB9,0x47,0x20,0xB6,0x28,0xBB,0xFF,0x0F};
const uint8_t sp_TEEN[] PROGMEM = {0x09,0x58,0x2A,0x25,0x00,0xCB,0x9F,0x95,0x6C,0x14,0x21,0x89,0xA9,0x78,0xB3,0x5B,0xEC,0xBA,0xB5,0x23,0x13,0x46,0x97,0x99,0x3E,0xD6,0xB9,0x2E,0x79,0xC9,0x5B,0xD8,0x47,0x41,0x53,0x1F,0xC7,0xE1,0x9C,0x85,0x54,0x22,0xEC,0xFA,0xDB,0xDD,0x23,0x93,0x49,0xB8,0xE6,0x78,0xFF,0x3F};
const uint8_t spA[] PROGMEM = {0x65,0x2C,0x96,0xAD,0x7B,0x6A,0x9F,0x66,0xE4,0x20,0x8D,0x9C,0x73,0xAB,0x5B,0xDC,0xE2,0x96,0xB7,0xBA,0xF5,0x6A,0x66,0x28,0xA0,0xCE,0xD5,0xBB,0xDB,0xFD,0x1E,0xE6,0x38,0xA7,0x36,0xCF,0x9C,0x80,0x51,0x8B,0xEB,0x52,0xD7,0xBC,0xFF,0x3F};
const uint8_t spB[] PROGMEM = {0xA6,0x2F,0xAA,0x05,0x5C,0xD6,0x8C,0xBC,0xC7,0x16,0x70,0x59,0x33,0xB2,0x95,0x0B,0xC1,0xFD,0xCD,0xCC,0x66,0x3A,0xF3,0x51,0xAD,0x98,0x00,0x55,0x8B,0x67,0xDB,0xC7,0x3E,0xD5,0xAD,0xEE,0x75,0x2F,0xE7,0x2C,0x4D,0x60,0xBE,0x26,0xDF,0xF1,0x89,0xEF,0xFF,0x03};
const uint8_t spC[] PROGMEM = {0x04,0xF8,0xA5,0x83,0x03,0x12,0xB0,0x80,0x07,0x22,0xB0,0xC2,0xEE,0x8D,0x45,0x7D,0xC9,0xCA,0x67,0x29,0x42,0xF5,0x35,0x3B,0xDF,0xF9,0x28,0x66,0x0D,0x40,0xCF,0xD7,0xB3,0x1C,0xCD,0xAC,0x06,0x14,0xB5,0x68,0x0E,0x7D,0xEE,0x4B,0xDF,0xD2,0x39,0x5B,0x02,0x44,0xBD,0xCE,0x57,0xBE,0xF2,0x9D,0xEE,0x55,0x0A,0xC1,0x73,0x4D,0x7E,0xF2,0xF3,0xFF};
const uint8_t spD[] PROGMEM = {0x06,0x98,0x30,0x68,0xE4,0x6B,0x84,0xA0,0xE8,0xD3,0x93,0x8D,0xEC,0x84,0x9E,0x4B,0x6E,0x36,0x8A,0x19,0x0D,0xA8,0xEA,0x71,0xAF,0x7A,0xDF,0xE7,0xB2,0xAD,0xE0,0x00,0xD3,0x8B,0xEB,0x9E,0x8F,0x7C,0xA6,0x73,0xE5,0x40,0xA8,0x5A,0x1C,0xAF,0x78,0xC5,0xDB,0xDF,0xFF,0x0F};
const uint8_t spE[] PROGMEM = {0xA2,0x59,0x95,0x51,0xBA,0x17,0xF7,0x6A,0x95,0xAB,0x38,0x42,0xE4,0x92,0x5D,0xEE,0x62,0x15,0x33,0x3B,0x50,0xD6,0x92,0x5D,0xAE,0x6A,0xC5,0x04,0xA8,0x5A,0xBC,0xEB,0xDD,0xEC,0x76,0x77,0xBB,0xDF,0xD3,0x9E,0xF6,0x32,0x97,0xBE,0xF5,0xAD,0xED,0xB3,0x34,0x81,0xF9,0x9A,0xFF,0x07};
const uint8_t spF[] PROGMEM = {0xAB,0x1B,0x61,0x94,0xDD,0xD6,0xDC,0xF1,0x74,0xDD,0x37,0xB9,0xE7,0xEA,0xD3,0x35,0xB3,0x1C,0xE1,0xAF,0x6F,0x77,0xC7,0xB5,0xD4,0xE0,0x56,0x9C,0x77,0xDB,0x5A,0x9D,0xEB,0x98,0x8C,0x61,0xC0,0x30,0xE9,0x1A,0xB0,0x80,0x05,0x14,0x30,0x6D,0xBB,0x06,0x24,0x20,0x01,0x0E,0x10,0xA0,0x06,0xB5,0xFF,0x07};
const uint8_t spG[] PROGMEM = {0x6E,0x3F,0x29,0x8D,0x98,0x95,0xCD,0x3D,0x00,0xAB,0x38,0x95,0xE2,0xD4,0xEB,0x34,0x81,0x7A,0xF2,0x51,0x53,0x50,0x75,0xEB,0xCE,0x76,0xB6,0xD3,0x95,0x8D,0x92,0x48,0x99,0xAB,0x77,0xBE,0xCB,0xDD,0x8E,0x71,0x96,0x04,0x8C,0x5A,0x3C,0xE7,0x39,0xF7,0xAD,0x6E,0xF5,0x2A,0xD7,0x2A,0x85,0xE0,0xB9,0x26,0x3E,0xF1,0xF9,0x7F};
const uint8_t spH[] PROGMEM = {0x65,0x18,0x6D,0x90,0x2D,0xD6,0xEC,0xF6,0x56,0xB7,0xBC,0xC5,0xAE,0xC7,0x30,0xA3,0x01,0x6D,0x2D,0xCE,0x8B,0x3D,0xDC,0xD6,0x3C,0x61,0x76,0xC5,0x25,0x9B,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x80,0x01,0x2B,0x87,0x38,0x60,0xE5,0xED,0x08,0x58,0xC0,0x02,0x16,0xB0,0x80,0x06,0x34,0x40,0x80,0x76,0xD3,0xFE,0x1F};
const uint8_t spI[] PROGMEM = {0xAA,0x8D,0x63,0xA8,0xAA,0x66,0xAD,0xB9,0xA8,0xCB,0x08,0xDD,0x7C,0xFB,0x5B,0xDF,0xFA,0x36,0xB7,0x39,0x6D,0xB5,0xA3,0x15,0xBA,0xF8,0x76,0xBB,0xDF,0xD3,0x9E,0xD7,0xDA,0x5C,0x49,0xA5,0x2D,0xDE,0x7B,0xDB,0x6B,0x76,0x29,0xAF,0xC7,0x6D,0xEF,0x31,0xD8,0x5C,0x1E,0xF7,0xBD,0x1E,0xF5,0x48,0xE7,0x28,0x89,0xE2,0xF2,0x38,0x5F,0xF9,0xFE,0x7F};
const uint8_t spL[] PROGMEM = {0x6B,0x68,0x2E,0xD8,0x2A,0x37,0xDF,0xFE,0xF6,0xA7,0xAF,0x21,0xBC,0xC4,0x17,0xDF,0xFE,0xF6,0x67,0xC8,0x6A,0xC3,0x4D,0x3A,0xDF,0x61,0x4D,0x95,0x6C,0xA6,0x71,0x9E,0xB1,0x36,0x98,0x53,0x49,0x5E,0xFB,0x5A,0x8E,0x0A,0x7A,0x43,0xD9,0x4F,0x3C,0xC2,0x59,0xE0,0xF4,0x08,0xF9,0x09,0x67,0x03,0x31,0x19,0xA2,0x25,0x9E,0xFF,0x0F};
const uint8_t spJ[] PROGMEM = {0x6E,0x5A,0xC1,0x99,0x54,0xB2,0x09,0x60,0x49,0x22,0x07,0xEC,0xA8,0x16,0x80,0x5D,0x26,0xC7,0xD0,0xA3,0x92,0x78,0x74,0x3E,0x55,0x2F,0x21,0x6A,0xB1,0xFA,0x56,0xB7,0xBA,0xD5,0xAD,0x6F,0x7D,0xBB,0x3D,0x8E,0x75,0xB4,0x22,0x36,0x7F,0x53,0xCF,0x7E,0xB5,0x67,0x96,0x61,0x34,0xDB,0x52,0x9F,0xF4,0x8E,0xDC,0x88,0xE1,0x5F,0xF2,0x9D,0xEF,0xFF,0x07};
const uint8_t spK[] PROGMEM = {0x01,0x18,0x91,0xB9,0x00,0x4D,0x91,0x46,0x60,0x65,0x2D,0xB3,0xB8,0x67,0xED,0x53,0xF4,0x14,0x64,0x11,0x4B,0x6E,0x79,0x8B,0x5B,0xDE,0xF2,0x74,0xC3,0x05,0x6A,0xE7,0xEA,0x3D,0xEC,0x71,0x2F,0x6D,0x1F,0xB1,0x00,0x2B,0xDF,0xF4,0xA3,0x1D,0xB3,0x24,0x60,0xD4,0xE2,0x7A,0xE5,0x2B,0xDF,0xE9,0x1E,0x43,0x48,0xA3,0xEB,0xE4,0xFB,0xFF,0x01};
const uint8_t spM[] PROGMEM = {0xA9,0xE8,0xC5,0xD8,0x73,0x16,0xCF,0xE2,0x0E,0xB7,0xBB,0xCD,0xA9,0xBB,0x6F,0xF1,0xF0,0xD5,0xB7,0xBE,0xCD,0xEE,0xC6,0x50,0x63,0x72,0x98,0x58,0xEE,0x73,0x5F,0xDB,0xD6,0x62,0x72,0x98,0x58,0xAE,0x7B,0xDD,0xD3,0x5E,0x45,0x72,0x93,0xD8,0x8D,0x87,0x3D,0xEC,0x61,0xCF,0x70,0x96,0x58,0xE1,0xA2,0x4D,0xE2,0x15,0xEF,0xFF,0x07};
const uint8_t spN[] PROGMEM = {0x41,0xEE,0xD1,0xC8,0xB3,0x16,0xEF,0xEE,0xD4,0xC3,0x35,0x59,0xC4,0xE3,0x5B,0xDD,0xEA,0x56,0xBB,0x59,0xED,0x92,0xCD,0x91,0xB4,0x78,0x4F,0x63,0x19,0x9E,0x38,0x2C,0x9C,0xCE,0xA5,0xAF,0xF5,0x08,0xC7,0xB0,0xC2,0x61,0x1E,0x35,0x1E,0xF1,0x8C,0x57,0xBC,0xD3,0xDD,0x4D,0x49,0xB8,0xCE,0x0E,0xF7,0x34,0xAD,0x16,0xBC,0xF9,0xFF,0x01};
const uint8_t spO[] PROGMEM = {0xA3,0x6D,0xB4,0xBA,0x8D,0xBC,0xAD,0xA6,0x92,0xEC,0x0E,0xF2,0xB6,0xAB,0x5D,0x8C,0xA2,0xE0,0xEE,0x16,0xF6,0x3F,0xCB,0x39,0xCC,0xB1,0xAC,0x91,0xE5,0x0C,0x8B,0xBF,0xB0,0x3B,0xD3,0x1D,0x28,0x59,0xE2,0xE9,0x4F,0x7B,0xF9,0xE7,0xFF,0x01};
const uint8_t spP[] PROGMEM = {0x02,0x88,0x26,0xD4,0x00,0x6D,0x96,0xB5,0xB8,0x25,0x05,0x89,0x6C,0x3D,0xD2,0xE6,0x51,0xB3,0xA6,0xF4,0x48,0x67,0x09,0xA0,0x8C,0xC7,0x33,0x9B,0x79,0xCB,0x67,0x0E,0x80,0xCA,0xD7,0xBD,0x6A,0xD5,0x72,0x06,0xB4,0xB5,0xBA,0xB7,0xBD,0xAF,0x73,0x5D,0xF3,0x91,0x8F,0x78,0xFE,0x3F};
const uint8_t spQ[] PROGMEM = {0x0E,0x98,0xD5,0x28,0x02,0x11,0x18,0xE9,0xCC,0x46,0x98,0xF1,0x66,0xA7,0x27,0x1D,0x21,0x99,0x92,0xB6,0xDC,0x7C,0x17,0xAB,0x2C,0xD2,0x2D,0x13,0x3B,0xEF,0xAA,0x75,0xCE,0x94,0x47,0xD0,0xEE,0x3A,0xC4,0x29,0x2F,0x61,0x35,0x31,0xA2,0x50,0xB6,0xF8,0xCD,0x1F,0xFF,0x0F};
const uint8_t spR[] PROGMEM = {0xAB,0xC8,0x72,0x33,0x93,0xBB,0xDC,0xEE,0xB6,0xB7,0xB9,0xF5,0x68,0x53,0x5C,0xA9,0xA6,0x4D,0xB3,0x6B,0x73,0x0A,0xCB,0x71,0xD8,0xBB,0xAF,0x7D,0x2F,0x47,0xB6,0xC7,0xF4,0x94,0x37,0x9D,0xA9,0x34,0xF8,0x53,0x97,0x78,0xFD,0x3F};
const uint8_t spS[] PROGMEM = {0x6B,0x6E,0xD9,0x34,0x6C,0xE6,0xDC,0xF6,0x36,0xB7,0xBE,0xF5,0x19,0xAA,0x0F,0x2D,0xDA,0x25,0x7B,0x19,0x5B,0x4D,0x9A,0xA2,0xE7,0xB8,0x1D,0x23,0xA5,0x26,0x71,0x2A,0x03,0xFC,0x94,0xE6,0x01,0x0F,0x68,0x40,0x03,0x12,0xE0,0x00,0x07,0x30,0xF0,0xFF};
const uint8_t spT[] PROGMEM = {0x01,0xD8,0xB6,0xDD,0x01,0x2F,0xF4,0x38,0x60,0xD5,0xD1,0x91,0x4D,0x97,0x84,0xE6,0x4B,0x4E,0x36,0xB2,0x10,0x67,0xCD,0x19,0xD9,0x2C,0x01,0x94,0xF1,0x78,0x66,0x33,0xEB,0x79,0xAF,0x7B,0x57,0x87,0x36,0xAF,0x52,0x08,0x9E,0x6B,0xEA,0x5A,0xB7,0x7A,0x94,0x73,0x45,0x47,0xAC,0x5A,0x9C,0xAF,0xFF,0x07};
const uint8_t spU[] PROGMEM = {0xA1,0x9F,0x9C,0x94,0x72,0x26,0x8D,0x76,0x07,0x55,0x90,0x78,0x3C,0xEB,0x59,0x9D,0xA2,0x87,0x60,0x76,0xDA,0x72,0x8B,0x53,0x36,0xA5,0x64,0x2D,0x7B,0x6E,0xB5,0xFA,0x24,0xDC,0x32,0xB1,0x73,0x1F,0xFA,0x1C,0x16,0xAB,0xC6,0xCA,0xE0,0xB5,0xDF,0xCD,0xA1,0xD4,0x78,0x1B,0xB6,0x53,0x97,0x74,0xA7,0x21,0xBC,0xE4,0xFF,0x01};
const uint8_t spV[] PROGMEM = {0x66,0xF3,0xD2,0x38,0x43,0xB3,0xD8,0x2D,0xAC,0x4D,0xBB,0x70,0xB0,0xDB,0xB0,0x0E,0x17,0x2C,0x26,0xAE,0xD3,0x32,0x6C,0xBB,0x32,0xAB,0x19,0x63,0xF7,0x21,0x6C,0x9C,0xE5,0xD4,0x33,0xB6,0x80,0xCB,0x9A,0x9B,0xAF,0x6C,0xE5,0x42,0x70,0x7F,0xB3,0xB3,0x9D,0xEE,0x7C,0x55,0x2B,0x26,0x40,0xD5,0xE2,0xD9,0xF6,0xB1,0x4F,0x75,0xAB,0x7B,0x3D,0xCA,0x35,0x4B,0x13,0x98,0xAF,0xA9,0x57,0x7E,0xF3,0x97,0xBE,0x19,0x0B,0x31,0xF3,0xCD,0xFF,0x03};
const uint8_t spW[] PROGMEM = {0xA1,0xDE,0xC2,0x44,0xC2,0xFC,0x9C,0x6A,0x88,0x70,0x09,0x59,0x7B,0x8A,0xCA,0x3B,0x3D,0xA4,0xCF,0xCD,0x56,0x96,0xC4,0xA6,0xBB,0xF4,0x6E,0x59,0xE2,0x9D,0xEA,0xE2,0x4A,0xD5,0x12,0x65,0xBB,0xB3,0xEB,0x51,0x57,0x12,0x99,0xC1,0xD9,0x6E,0xB7,0xC7,0x31,0x35,0x92,0x6A,0xC9,0x9B,0xC7,0x34,0x4C,0x12,0x46,0x6C,0x99,0x73,0x5F,0xDA,0xD2,0x92,0x92,0x64,0x6C,0xEE,0x6B,0xD9,0x6A,0x22,0x71,0x8F,0xCF,0xE5,0x2C,0x41,0xD4,0xDD,0x36,0xA5,0x3B,0x19,0xF5,0x0C,0xEE,0x13,0xEF,0xFC,0x9A,0xD7,0x85,0xC8,0x62,0xEE,0x6D,0xBF,0xFF,0x07};
const uint8_t spX[] PROGMEM = {0xAD,0x68,0xC9,0xC5,0x32,0x56,0xDF,0xFA,0x54,0x2D,0x35,0x7B,0xF8,0xEA,0x5B,0xDD,0xE6,0x4C,0x6D,0x04,0xA6,0xC5,0xEA,0xB9,0x84,0xB5,0x75,0x23,0x37,0x4F,0x83,0x40,0x11,0xCA,0x5D,0x44,0x36,0x00,0x28,0xA0,0xE6,0x31,0x0F,0x68,0xC0,0x00,0xBF,0x8D,0x79,0xC0,0x03,0x16,0xD0,0x00,0x07,0xFE,0x1F};
const uint8_t spY[] PROGMEM = {0x6A,0xB1,0xA2,0xA7,0x95,0xD2,0xD8,0x25,0x0F,0xA3,0x2D,0xB2,0x7A,0x1C,0xB3,0xDE,0xE6,0xD4,0x45,0x6D,0x56,0xCA,0x9A,0x5B,0xDF,0xFA,0xB6,0xBB,0xDB,0xFD,0x1A,0x8A,0x6F,0x2B,0xF3,0x37,0x7B,0x19,0x4B,0xD3,0x25,0x39,0xFA,0xB9,0x6F,0x6D,0xEB,0x31,0xC4,0x5C,0x1E,0xF7,0xAD,0x1F,0xE5,0x1C,0xA5,0x48,0x5C,0x1E,0xD7,0x2B,0x5F,0xF9,0xFA,0x7F};
const uint8_t spZ[] PROGMEM = {0x6D,0xFD,0xC6,0x5C,0x95,0xD5,0xF5,0xD5,0x02,0x7B,0x5D,0xFD,0x51,0x2D,0x2A,0xE4,0x77,0x75,0xA3,0x3A,0xB1,0xFA,0x9B,0x5D,0xEF,0x6A,0x55,0x33,0x27,0x60,0xD4,0xE2,0xD9,0xCC,0x76,0x4E,0x73,0x9D,0x7B,0x3F,0xFB,0x59,0xAE,0x55,0x0A,0xC1,0x73,0x4D,0xBD,0xEA,0x9D,0x9E,0x15,0x12,0xA0,0x6B,0x75,0x7E,0xFE,0x1F};
const uint8_t spALPHA[] PROGMEM = {0xAD,0xED,0x6A,0xDC,0x4B,0x57,0xEF,0xF6,0xB4,0x53,0x6C,0x6A,0x4B,0x97,0x53,0x77,0x7E,0x19,0xC9,0x9B,0x57,0x99,0xCC,0x7B,0x9A,0x6E,0x9E,0x45,0x2B,0xA2,0xA9,0x0A,0x91,0xCC,0xB5,0x00,0x02,0x14,0x67,0xA1,0x80,0x16,0x2C,0x3C,0x60,0x80,0xE6,0x2C,0x4A,0x51,0x54,0x47,0x38,0x6F,0xDE,0xC3,0x5D,0xF6,0x36,0xF7,0x7A,0xE5,0xFB,0xFF,0x01};
const uint8_t spBRAVO[] PROGMEM = {0x61,0x5A,0xBA,0xC2,0xDD,0x62,0x85,0xD6,0xE8,0x15,0x59,0xB1,0x97,0x9A,0x30,0xD5,0xBC,0x85,0xDF,0xA8,0x63,0x0F,0xE9,0x50,0xE5,0xA7,0xCA,0x6E,0x22,0x5D,0x57,0xEF,0x72,0x97,0xB3,0x2A,0x6D,0x74,0x15,0xE9,0xBA,0x3A,0xF6,0x66,0xE8,0x3E,0xD4,0x5C,0x65,0xD7,0x31,0x2D,0x95,0x54,0xBB,0x8B,0xDF,0xD9,0xAE,0xB1,0xA1,0xAC,0x0E,0x51,0x3F,0xE7,0xB6,0x14,0xD2,0x35,0x4E,0xEE,0xFB,0x5E,0x77,0xB3,0x7B,0xDF,0x19,0x2C,0x7D,0xEC,0xE9,0x2F,0x73,0x05,0xDF,0x19,0x2C,0x7D,0xF8,0xF3,0xFF};
const uint8_t spCHARLIE[] PROGMEM = {0x06,0xD8,0x2D,0x2C,0x01,0x33,0xB7,0x67,0x60,0xC4,0x35,0x94,0xAA,0x5A,0xEA,0x93,0x15,0xD7,0xAA,0x23,0xEE,0x56,0x9E,0xD3,0xAA,0x2E,0xE5,0xDB,0xF9,0xC8,0x4B,0x6A,0x8E,0xE3,0x3E,0x33,0x2F,0x45,0x6E,0x62,0x39,0x9A,0x76,0x74,0x4D,0xA5,0xA5,0x73,0xD2,0x3B,0xAC,0xA9,0xD9,0x61,0x0D,0xDF,0x32,0xE6,0xEE,0x0A,0x39,0xE3,0xF3,0x58,0x97,0x2D,0xC2,0x8C,0x2D,0x7D,0x4D,0xE7,0xCC,0x09,0x18,0xB5,0x38,0x5E,0xFE,0xFE,0x7F};
const uint8_t spDELTA[] PROGMEM = {0x02,0xE8,0x54,0x6D,0xB5,0x35,0x84,0xB9,0xDA,0x9A,0x5B,0x9F,0xAA,0x98,0x71,0x77,0xDB,0x7C,0x8A,0x64,0x2F,0x5C,0xBD,0xF7,0xCA,0x33,0x9F,0x4A,0x95,0x2C,0x2D,0xCB,0xD2,0xAA,0x95,0xDD,0x9A,0x7C,0x7B,0x15,0xD2,0x48,0x8C,0x40,0x11,0xCA,0x5D,0x44,0x36,0x28,0xE0,0x47,0x73,0x01,0x24,0xEA,0xB2,0xBA,0x6A,0xC2,0xC3,0x7C,0xCB,0x1D,0xCF,0xD6,0x54,0xA5,0x87,0x74,0xDD,0xE7,0xBA,0xAB,0x1A,0xF3,0x94,0xCE,0xFD,0xC9,0xEF,0xFF,0x03};
const uint8_t spECHO[] PROGMEM = {0x2B,0x6F,0xB1,0xD9,0xD3,0x36,0xDF,0xF6,0x36,0xB7,0x26,0x85,0x08,0xE5,0x2E,0x22,0x1B,0x20,0x00,0x25,0xAC,0x2A,0x20,0xCF,0xD3,0x52,0x45,0x53,0x6A,0xA9,0x9E,0x4F,0x9B,0x54,0x47,0xB9,0xE4,0xDF,0xC3,0x1C,0xC6,0x98,0x45,0x65,0xBB,0x78,0x9F,0xCB,0x5C,0xD2,0xEA,0x43,0x67,0xB0,0xE5,0xCD,0x7B,0x38,0x9D,0xAD,0x2C,0x15,0x37,0xF1,0xFC,0x7F};
const uint8_t spFOXTROT[] PROGMEM = {0x08,0x98,0xB1,0x53,0x02,0x1E,0x88,0xC0,0xCA,0x8B,0xDA,0x4A,0x97,0x2E,0xB7,0xBA,0xD5,0x2A,0x73,0xE8,0x48,0xD3,0xCD,0xAD,0xA8,0x35,0xA2,0xC5,0xAA,0x90,0x42,0x84,0x72,0x17,0x91,0x0D,0x0A,0xA8,0xA1,0xC5,0x01,0xAF,0xF8,0x78,0x40,0x01,0x6F,0xB5,0x23,0xA0,0x47,0x53,0x0C,0x44,0xC0,0x03,0xAD,0x49,0x85,0x53,0x53,0xDD,0x8D,0x26,0x56,0xCB,0x70,0xCD,0xB7,0xA6,0x64,0xC7,0x2B,0x39,0xEF,0x5A,0xAA,0xB8,0xF4,0xE2,0x3E,0xF3,0x1C,0x57,0x0E,0x1D,0x69,0xBA,0xD9,0x5F,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x80,0x00,0x8E,0xE0,0x30,0xC0,0xB2,0x53,0x04,0xA8,0xCA,0xE5,0xFF,0x01};
const uint8_t spGOLF[] PROGMEM = {0x0A,0x88,0xA1,0x71,0x15,0x85,0x76,0x45,0x8A,0xFF,0x9B,0xDF,0x6C,0x65,0x99,0x5C,0xB7,0x72,0xDE,0x9D,0xED,0x72,0x77,0x73,0x6C,0x4B,0x54,0x35,0x63,0xE4,0xA6,0xEE,0xF9,0x34,0x57,0x94,0x39,0x63,0xE4,0x86,0x5F,0x04,0x98,0x34,0xDD,0x02,0x0E,0x98,0x32,0x5D,0x03,0x12,0xE0,0xC0,0xFF,0x03};
const uint8_t spHENRY[] PROGMEM = {0x08,0xC8,0x4A,0x8C,0x03,0x1A,0x68,0x49,0x0B,0xAC,0xE5,0x11,0xFA,0x14,0xCD,0x35,0x59,0xC4,0xE3,0x5B,0xEC,0xBC,0xA5,0xD5,0x88,0x96,0x99,0xBD,0x9E,0x95,0x3C,0x1B,0xB3,0x64,0x69,0x1A,0xEB,0xD2,0xA7,0xA9,0x1C,0xE6,0xD1,0xDB,0x98,0x07,0xA7,0x5A,0xAA,0x5F,0x53,0x4D,0xAA,0x61,0x9E,0x7D,0xAC,0xDD,0x8E,0x48,0xC8,0x9E,0xB1,0x77,0x5B,0x44,0x95,0xAB,0xEB,0x15,0xAE,0x1E,0x0D,0x2D,0xF3,0x4D,0x7C,0xFC,0xF3,0xFF};
const uint8_t spINDIA[] PROGMEM = {0xA3,0x9D,0xD6,0x99,0x32,0x17,0xAF,0x66,0x86,0x16,0x74,0x5F,0x73,0x9A,0xE1,0x4A,0xC4,0xF4,0xCE,0xAD,0x46,0xD1,0x1D,0x5A,0x46,0x3A,0x99,0x45,0x2B,0xAA,0x82,0xAC,0x08,0x27,0xBE,0x5A,0xDD,0x0C,0x25,0x42,0xBC,0xFB,0xF4,0xD3,0x17,0x61,0xF8,0x96,0x3B,0xDC,0xF1,0x4C,0xDD,0x26,0x4B,0xD9,0x9E,0xBB,0xAC,0xB5,0xBB,0x36,0x0D,0xDA,0x7B,0xF6,0xA6,0xD3,0x3A,0xA5,0xF7,0x7E,0xE7,0x3B,0xBF,0xF2,0x55,0x17,0xD6,0xCE,0xAB,0xFD,0xFF,0xFF};
const uint8_t spJULIET[] PROGMEM = {0x61,0x5D,0x96,0x49,0x34,0xD2,0x06,0x60,0xC7,0x90,0x0C,0x8C,0x66,0xF6,0x15,0x22,0x4D,0x37,0xAA,0x6A,0xC8,0x2C,0x6D,0xCD,0x28,0xB2,0x15,0x8B,0xE4,0x35,0xB3,0x68,0x79,0x51,0xE6,0xDA,0x9C,0xBE,0x15,0x43,0x89,0xF0,0xA2,0xDB,0x95,0x77,0xA7,0xA6,0x66,0x49,0x77,0xB1,0x9A,0x9E,0x0A,0xD5,0x75,0xEB,0xEE,0xF6,0xB0,0xC6,0xE6,0x83,0xD2,0xE3,0xEB,0x5E,0xD7,0xDA,0x5C,0x48,0x87,0x6D,0x9E,0x7B,0xDF,0xF3,0x89,0x40,0x11,0xCA,0x5D,0x44,0x36,0x00,0x38,0x60,0xEA,0x8C,0x00,0x2C,0xB3,0x6D,0x01,0x01,0x14,0x5F,0x8E,0x81,0xFF,0x07};
const uint8_t spLIMA[] PROGMEM = {0x61,0x5A,0x90,0xBA,0xC0,0xD7,0xA6,0x69,0x00,0x19,0x85,0x6A,0xDA,0x9A,0xCD,0x24,0xD9,0xCC,0xCB,0x29,0x46,0x76,0x66,0xF5,0x37,0x3B,0x9B,0xC9,0x48,0x7B,0x50,0xD4,0x8E,0xD9,0xBD,0xA8,0x75,0x6B,0xB3,0x62,0xEE,0xF4,0xB8,0xB5,0xAD,0xFD,0x98,0x8A,0x51,0x0E,0x91,0xB4,0xA3,0x6F,0xBC,0x32,0x8B,0x3A,0xDF,0xE1,0xEE,0xE3,0xCC,0x6A,0x23,0x43,0x57,0xF5,0xA7,0xBE,0xF5,0xFD,0x7F};
const uint8_t spMIKE[] PROGMEM = {0x66,0x31,0x3C,0x7C,0x52,0xE3,0xC4,0x69,0xF5,0x85,0x57,0x86,0x51,0xAA,0xD3,0x56,0x75,0xA1,0x69,0x9D,0x6F,0x7D,0xCA,0x6A,0x57,0x23,0x6D,0xF5,0xCD,0x57,0xD1,0x4B,0x50,0x78,0x2C,0xDA,0x75,0x69,0x46,0x77,0xB4,0xCE,0xDB,0xB1,0x45,0xAD,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x18,0xD0,0x3C,0x91,0x03,0x5A,0x09,0xB1,0x80,0x00,0xB2,0x13,0xFE,0x7F};
const uint8_t spNOVEMBER[] PROGMEM = {0x6A,0x2B,0x02,0x62,0x4B,0xE3,0xDA,0x75,0x2C,0x5D,0x87,0xB8,0x73,0x9B,0xD5,0x66,0x1D,0x16,0x66,0x7D,0x57,0x9B,0x45,0x59,0x07,0xB7,0x6B,0x55,0xB0,0x99,0xCD,0x9C,0xAD,0x56,0xA1,0x88,0xCE,0x3A,0x99,0x33,0xFB,0xC5,0xCC,0xD5,0xA8,0xA5,0xA9,0x1B,0xDF,0x8E,0xBA,0x05,0xB3,0x34,0xED,0x7C,0xCB,0x9B,0x8F,0xAC,0x38,0xCB,0x0C,0x6D,0x5C,0xB2,0xA2,0x94,0xDA,0xCD,0x4D,0x2C,0x55,0x2B,0x75,0x4A,0xA7,0xBB,0xD5,0x3D,0xA4,0x2D,0x77,0xE5,0x2A,0xEE,0x9C,0xD7,0xB4,0x65,0x77,0xA0,0x9B,0xFA,0xE2,0x9E,0xAE,0x5C,0x0B,0xAA,0xD4,0xB7,0xBF,0xFD,0x6D,0x9E,0xE2,0x1A,0x7C,0x43,0xAF,0x7A,0xCB,0x30,0xCA,0xE6,0x2D,0xFF,0x0F};
const uint8_t spOSCAR[] PROGMEM = {0x6B,0xC8,0xE2,0xB2,0x42,0x3A,0xDF,0xFA,0x16,0x27,0x4F,0xAE,0x7D,0xC4,0x17,0xB7,0x2C,0x45,0xAF,0xA4,0xB6,0x6D,0x80,0x03,0xD8,0x0C,0xF0,0xA7,0x9B,0x07,0x3C,0xE0,0x80,0xEB,0xB5,0xC1,0x6C,0x4D,0x5D,0x45,0x69,0xDC,0xD4,0x17,0x37,0x49,0x26,0x4A,0x5B,0x9B,0x53,0x91,0x0D,0xE7,0x9D,0xFD,0x1C,0xDB,0x92,0x9B,0x61,0xB5,0xF4,0x9E,0x5B,0xDD,0xEB,0x99,0xEE,0x12,0x07,0x75,0x52,0x6F,0xFE,0xC2,0x5F,0x5A,0x91,0x0E,0x67,0xF9,0x7F};
const uint8_t spPAPA[] PROGMEM = {0x0A,0x70,0x4A,0xB5,0xA5,0x45,0x55,0x84,0x49,0xCC,0x93,0x66,0xD7,0x19,0x26,0x4B,0x4E,0x96,0xDD,0x44,0xBA,0xAE,0xBE,0xD9,0xCC,0x10,0x28,0x42,0xB9,0x8B,0xC8,0x06,0x60,0x80,0xF1,0xE9,0xAB,0xCA,0xA6,0x23,0xD4,0x36,0xDF,0xE1,0x8C,0x55,0x74,0x86,0x6B,0x9F,0xB1,0x67,0xBD,0xE1,0xE6,0xBB,0xDB,0x97,0x53,0x45,0x88,0xCF,0xAE,0xDF,0xFF,0x03};
const uint8_t spQUEBEC[] PROGMEM = {0x0C,0x88,0x7E,0x8C,0x02,0xA5,0x0A,0x31,0xDD,0x5C,0xB2,0xAC,0x26,0x5B,0xCF,0x4C,0xEE,0xBB,0xBB,0xDE,0xA7,0xCD,0xA8,0xB4,0x75,0x4D,0x1C,0xB7,0xD1,0xD5,0x28,0xEE,0xE6,0x5B,0x76,0x7B,0x9A,0x1A,0xC4,0x33,0xF3,0xF1,0x6D,0x76,0x3F,0xE7,0xB6,0xB6,0xEC,0x12,0x91,0x9B,0xF2,0x8E,0x40,0x11,0xCA,0x5D,0x44,0x36,0x80,0x00,0x7A,0x2F,0x53,0x40,0x2D,0x24,0x14,0xF8,0x7F};
const uint8_t spROMEO[] PROGMEM = {0xA2,0xD5,0x39,0x38,0xCA,0xEC,0xDB,0xA5,0x4C,0xA1,0x98,0x5A,0xB9,0xF2,0xD3,0x47,0x6F,0xE9,0x69,0xCA,0x4E,0xDD,0x89,0x57,0x0E,0x69,0x3F,0x45,0x61,0xD9,0x95,0x98,0x65,0x67,0x25,0x6B,0x86,0x64,0x4C,0xAC,0xF5,0xE2,0x54,0xCD,0x86,0x7A,0xD0,0xE6,0x35,0x4C,0xD7,0x02,0xA5,0x7B,0xF6,0xB0,0xA7,0xBD,0xAC,0xB5,0xAA,0x54,0x1D,0xDB,0xB2,0xF6,0xEC,0xC3,0xD3,0x64,0x73,0xD9,0x63,0xC8,0x2C,0xD5,0xDF,0xE9,0x0C,0xA1,0x33,0xD8,0xF2,0xE6,0x33,0x5E,0xEE,0x09,0xB6,0xB2,0x54,0xDC,0xF8,0xE7,0xFF,0x01};
const uint8_t spSIERRA[] PROGMEM = {0x0C,0xF8,0xAD,0xDC,0x02,0x1E,0xB0,0x80,0x06,0x4A,0xDE,0x7D,0x90,0xB8,0xBD,0x1E,0xD5,0xC8,0x45,0xE8,0xF6,0x76,0x56,0xB3,0xDE,0xF5,0xAD,0x4F,0x35,0x72,0xB1,0xB8,0xAE,0x39,0x65,0x0F,0x45,0x56,0xFA,0xE5,0xE4,0x25,0x24,0xE5,0xC8,0xE6,0x91,0xC6,0xC9,0x99,0x6E,0x69,0x7B,0xDA,0xF3,0xD5,0xA4,0xA4,0x95,0x6E,0x5D,0xF6,0xB0,0xB7,0xB5,0x17,0x5B,0xD6,0x2A,0x9B,0xC7,0x9D,0x5D,0x5B,0x9B,0xEF,0xEA,0x77,0x7D,0xCA,0x5F,0x55,0xD9,0x94,0xF4,0xFE,0x7F};
const uint8_t spTANGO[] PROGMEM = {0x0E,0x58,0x5A,0xC3,0x02,0x27,0xEB,0xA1,0xC4,0x2B,0x97,0xDC,0xF2,0x16,0x27,0xEF,0x51,0xB9,0x2A,0x2B,0xEF,0xAC,0x64,0x3D,0x60,0x79,0x99,0xE2,0x52,0x74,0x8F,0x9E,0x56,0xAA,0x43,0x99,0x24,0x75,0x5A,0x3A,0x0E,0x4D,0x31,0xC1,0xAC,0x96,0x24,0xCD,0x35,0x96,0x38,0xC9,0xAA,0xD6,0x25,0x17,0x96,0xA6,0xBB,0xE7,0xB0,0xA6,0x2C,0x2A,0xDB,0xC5,0xFB,0x9E,0xE6,0x92,0x76,0x1F,0x3A,0x83,0x2D,0x6F,0x3C,0xC3,0xE5,0x6C,0x65,0xA9,0xB8,0xF1,0xB7,0xBD,0xFF,0x1F};
const uint8_t spUNIFORM[] PROGMEM = {0x61,0x3D,0x56,0x98,0xD4,0xB6,0xE6,0xA5,0x8D,0xC7,0xA8,0x01,0xC5,0xDA,0x33,0x2C,0x97,0x06,0x12,0xD9,0x4F,0xD9,0x6D,0x30,0xA6,0x65,0xDF,0x79,0x4B,0x8B,0x11,0xCF,0xE0,0xAE,0x29,0xCD,0x4E,0x5D,0x38,0xEA,0xF5,0xF4,0x64,0x45,0x47,0x84,0xCA,0xE6,0x5D,0xF5,0x96,0x01,0xCD,0x97,0x6A,0x40,0x03,0x1A,0x28,0x5D,0xD0,0xDB,0x61,0xEC,0x7D,0xF7,0x7B,0x3C,0x53,0x16,0xDB,0x9A,0xEA,0xF5,0x2E,0x6B,0x2D,0x6A,0x43,0x46,0xBC,0xCD,0xB3,0x3D,0xD9,0xB5,0xDA,0x70,0xDF,0x72,0xE7,0x94,0xEA,0xCD,0x9D,0xDD,0x9D,0xBC,0x73,0xA9,0x28,0x35,0x4F,0x12,0x41,0xE1,0x96,0xD4,0x3D,0x4D,0x24,0xA7,0x8A,0x94,0xF8,0xFA,0x37,0x7C,0xCD,0x76,0x78,0x50,0xEA,0xF8,0xFD,0x3F};
const uint8_t spVICTOR[] PROGMEM = {0x6E,0x2D,0xCA,0xD8,0x43,0xD5,0x99,0xBD,0x58,0xE6,0x70,0xF1,0x9A,0x97,0xD5,0xB6,0x54,0xAA,0x26,0x7D,0x6E,0xB5,0xB2,0xD6,0x8D,0x4D,0x74,0xCB,0x4E,0x4D,0x3C,0xB2,0xAA,0x8B,0x38,0x16,0x40,0xE5,0x8C,0x18,0x40,0xA0,0x08,0xE5,0x2E,0x22,0x1B,0x0C,0xB0,0xED,0xA4,0x02,0xAA,0x15,0x5A,0x43,0xF5,0x21,0x54,0x96,0x6D,0x2C,0xA5,0x26,0x7A,0xB9,0xB7,0xBE,0xA5,0x27,0x57,0x87,0x2E,0xF7,0x1F,0xFE,0xDC,0x49,0xBB,0xBC,0x6F,0xFC,0xFD,0xEF,0xFF,0xFF,0x07};
const uint8_t spWHISKY[] PROGMEM = {0x04,0x88,0xAE,0x8C,0x03,0x12,0x08,0x51,0x74,0x65,0xE9,0xEC,0x68,0x24,0x59,0x46,0x78,0x41,0xD7,0x13,0x37,0x6D,0x62,0xC3,0x5B,0x6F,0xDC,0xD2,0xEA,0x54,0xD2,0xE3,0x89,0x01,0x7E,0x2B,0xF7,0x80,0x07,0x14,0xD0,0xE5,0x15,0x38,0x60,0x8C,0x70,0x03,0x04,0x29,0x36,0xBA,0x5E,0x14,0x34,0x72,0xF6,0xE8,0xA7,0x6F,0x82,0xF4,0x2D,0x73,0xEA,0x47,0x3A,0x67,0x6A,0xC0,0xF0,0x2F,0xF1,0x4E,0xCF,0xA8,0x8A,0x1C,0xB9,0xD8,0xFF,0xEE,0x1F,0xBB,0x59,0xD0,0xD6,0xFE,0x3F};
const uint8_t spXRAY[] PROGMEM = {0x69,0xAE,0xDE,0x34,0x3A,0x6B,0x9F,0xAC,0xA5,0x66,0x0F,0x5F,0x7D,0x8B,0x5B,0xAD,0xAA,0x8D,0xC0,0xB4,0x58,0xDD,0xDB,0xD0,0xB6,0x6E,0xE4,0xE6,0x69,0x10,0x28,0x42,0xB9,0x8B,0xC8,0x06,0x10,0x40,0xCD,0x63,0x1A,0x60,0xC0,0x6F,0x63,0x1C,0xA0,0x00,0x5B,0xFD,0x54,0xEA,0x54,0xE7,0x66,0x4E,0x8D,0xC3,0xD3,0xF4,0xE6,0xA9,0x4F,0x6B,0xAE,0x2E,0x39,0x42,0xFB,0xEE,0x6D,0x1C,0xCD,0x24,0x45,0xF9,0xE7,0x7E,0xF6,0x33,0x5F,0xF9,0x0A,0xCF,0xB4,0x4B,0x94,0xBE,0x27,0x3E,0xF1,0x75,0xEF,0xCC,0x09,0x18,0xB5,0xF8,0xFF,0x01};
const uint8_t spYANKEE[] PROGMEM = {0x6E,0xEF,0x42,0x58,0xB6,0x6B,0xA7,0x7D,0x68,0x25,0xCC,0x59,0xB4,0xF6,0x11,0x82,0xC8,0x6A,0xF1,0x1A,0x46,0x2E,0x12,0x8D,0x37,0xA7,0xEF,0xC9,0xC9,0xA3,0x6E,0x9F,0x76,0xD4,0x22,0x73,0x7F,0xB4,0xEA,0x51,0x0B,0x2D,0x62,0xE2,0xA8,0x47,0x43,0xD7,0x2E,0x29,0xAE,0x4D,0x92,0xAA,0x28,0x5C,0x8B,0xB9,0x6A,0xEB,0x24,0x95,0xE3,0x80,0x1D,0x93,0x35,0x90,0xBA,0x59,0x03,0x45,0xB3,0x75,0x19,0x46,0x27,0x96,0x98,0xC5,0x65,0x1F,0xCD,0x88,0xBC,0x16,0xD7,0x3D,0x3D,0x63,0x10,0x49,0x6E,0xED,0xF8,0xFA,0xEF,0xFF,0x01};
const uint8_t spZULU[] PROGMEM = {0x6D,0xFE,0xDE,0xC4,0xC4,0xE8,0x29,0x60,0x00,0x2E,0x0F,0x9C,0x6C,0x29,0x71,0x2A,0x4E,0x77,0x93,0x15,0x77,0x2A,0xAE,0xC3,0xCE,0x76,0x3C,0x92,0xA5,0x44,0x78,0xD1,0x6D,0xCF,0x47,0x3B,0xB8,0xBB,0x07,0xF6,0x5B,0x43,0x91,0x6E,0xA9,0xF2,0x65,0x4C,0xC9,0x98,0x97,0x69,0x9F,0xBA,0xE5,0x33,0x9C,0xC1,0x9A,0x8F,0xCA,0xDE,0x70,0x07,0x9D,0xEE,0xC9,0x79,0xE2,0xED,0xFF,0xFF,0x07};
const uint8_t spTHE[] PROGMEM = {0x6E,0xAD,0xCC,0x34,0x9C,0x97,0xE8,0x23,0xED,0x5D,0xA4,0xBB,0xF1,0x96,0xD9,0xEE,0xFA,0xD4,0x45,0x75,0xA6,0xC9,0xE6,0x5B,0xDF,0xE6,0x0E,0x67,0xAE,0x7C,0xD3,0x43,0xFB,0xEC,0x7D,0x9E,0xFD,0xFE,0x7F};
const uint8_t spWATTS[] PROGMEM = {0xAA,0x15,0x7A,0x23,0x5C,0x12,0xE9,0xD1,0x0D,0x5A,0x76,0x75,0xB2,0xAA,0xD0,0x3B,0xD9,0xED,0x81,0x99,0x4A,0x1B,0xD5,0x8C,0x25,0xFA,0xDD,0xF5,0xA9,0xA3,0x9F,0x2C,0xE3,0x2E,0xB7,0xBE,0xCD,0xEE,0xD6,0x9C,0xDC,0x44,0xAB,0xAD,0x6E,0x67,0x0E,0xE9,0xCD,0x7D,0xBB,0x1E,0x0C,0x1C,0x24,0xCA,0x5C,0x59,0x03,0x00,0x01,0xB6,0x2A,0x15,0xC0,0x2F,0x19,0x1A,0xB0,0x80,0x05,0x2C,0x60,0x80,0xAF,0xA2,0x24,0xF0,0xFF};
const uint8_t spMETER[] PROGMEM = {0xA1,0x8F,0x5C,0xB5,0x56,0x92,0xE4,0xE1,0xF4,0xDD,0x0B,0x59,0x6B,0xE3,0x53,0x8C,0x14,0x44,0x15,0x8B,0x46,0x3A,0xB3,0x03,0x7B,0xBE,0x99,0x89,0x49,0xB7,0x72,0xC4,0xEA,0x4C,0x01,0xD8,0x2E,0xC8,0x03,0xA3,0xAB,0x91,0x39,0x2C,0x17,0x8D,0xAE,0x36,0xE6,0x34,0x7F,0x3D,0xE6,0xEA,0x13,0x6C,0x79,0x73,0x3B,0xAA,0x1B,0xB0,0xD3,0x3C,0xFD,0x6A,0x4F,0xF1,0x09,0x35,0x9E,0xA5,0xBE,0xFF,0x0F};
const uint8_t spDANGER[] PROGMEM = {0x2D,0xBF,0x21,0x92,0x59,0xB4,0x9F,0xA2,0x87,0x10,0x8E,0xDC,0x72,0xAB,0x5B,0x9D,0x62,0xA6,0x42,0x9E,0x9C,0xB8,0xB3,0x95,0x0D,0xAF,0x14,0x15,0xA5,0x47,0xDE,0x1D,0x7A,0x78,0x3A,0x49,0x65,0x55,0xD0,0x5E,0xAE,0x3A,0xB5,0x53,0x93,0x88,0x65,0xE2,0x00,0xEC,0x9A,0xEA,0x80,0x65,0x82,0xC7,0xD8,0x63,0x0A,0x9A,0x65,0x5D,0x53,0xC9,0x49,0x5C,0xE1,0x7D,0x2F,0x73,0x2F,0x47,0x59,0xC2,0xDE,0x9A,0x27,0x5F,0xF1,0x8B,0xDF,0xFF,0x03};
const uint8_t spPRESSURE[] PROGMEM = {0x06,0x28,0xC1,0x4C,0x03,0x2D,0x49,0x59,0x4A,0x9A,0x3D,0x9F,0xAC,0x04,0x2D,0x2D,0x69,0x73,0xB2,0x56,0x4C,0x43,0x6D,0xF5,0xCD,0x5A,0x3E,0x6A,0x89,0x09,0x65,0x71,0xC0,0xAA,0xDB,0x1E,0x88,0x40,0x04,0x46,0xDF,0x63,0x0A,0x9A,0x65,0x1D,0x43,0xC9,0x49,0x5C,0xE1,0x7D,0xCF,0x7B,0x9F,0x47,0xB9,0xCA,0x12,0xF6,0xD6,0x3C,0xF9,0x8B,0x9F,0xFD,0xFF,0x1F};
const uint8_t spCHANGE[] PROGMEM = {0x06,0x58,0xD5,0xC3,0x01,0x73,0x6E,0x64,0xC0,0x03,0x2B,0x1B,0xB9,0x95,0xDC,0xFB,0xDE,0xE2,0x14,0xA3,0x06,0x4B,0xE5,0xA2,0x9B,0xEF,0x7C,0x95,0xC3,0x1B,0xCA,0x64,0xA5,0x5D,0xED,0x76,0xCE,0x7D,0x2D,0x6B,0xB3,0x24,0x19,0x11,0x3A,0x1D,0xDD,0x93,0x94,0x7A,0x54,0x7F,0xBA,0xBB,0x4B,0xC5,0x08,0xAD,0x1A,0x9E,0xEE,0x85,0x43,0x2D,0x9E,0x79,0xAA,0x10,0xCA,0xD2,0x2A,0xEA,0xC9,0x82,0xAC,0xC3,0x6B,0xCB,0x87,0x3D,0x51,0xB2,0x75,0x74,0x2D,0xF4,0xCE,0x30,0x2C,0x62,0x76,0x14,0x30,0x94,0x92,0x02,0xC6,0x5C,0xB7,0x00,0x02,0x5A,0x17,0xF9,0x7F};
const uint8_t spMINUS[] PROGMEM = {0xE6,0x28,0xC4,0xF8,0x44,0x9A,0xFB,0xCD,0xAD,0x8D,0x2A,0x4E,0x4A,0xBC,0xB8,0x8C,0xB9,0x8A,0xA9,0x48,0xED,0x72,0x87,0xD3,0x74,0x3B,0x1A,0xA9,0x9D,0x6F,0xB3,0xCA,0x5E,0x8C,0xC3,0x7B,0xF2,0xCE,0x5A,0x5E,0x35,0x66,0x5A,0x3A,0xAE,0x55,0xEB,0x9A,0x57,0x75,0xA9,0x29,0x6B,0xEE,0xB6,0xD5,0x4D,0x37,0xEF,0xB5,0x5D,0xC5,0x95,0x84,0xE5,0xA6,0xFC,0x30,0xE0,0x97,0x0C,0x0D,0x58,0x40,0x03,0x1C,0xA0,0xC0,0xFF,0x03};
const uint8_t spNOT[] PROGMEM = {0x66,0x6B,0x1A,0x25,0x5B,0xEB,0xFA,0x35,0x2D,0xCD,0x89,0xA7,0xDA,0x9A,0x31,0x34,0x93,0x9E,0xA6,0x4B,0x4E,0x57,0xE5,0x86,0x85,0x6C,0xBE,0xED,0x6D,0x57,0x93,0xFC,0xB9,0x96,0x2D,0x1E,0x4D,0xCE,0xAD,0xE9,0x3E,0x7B,0xF7,0x7D,0x66,0xB3,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x40,0x01,0x4B,0xB8,0x2B,0xE0,0x87,0x68,0x05,0x74,0x9D,0x82,0x80,0x62,0x55,0xFE,0x1F};
const uint8_t spSTART[] PROGMEM = {0x04,0xF8,0xC5,0x9C,0x03,0x1A,0xD0,0x80,0x04,0x38,0x00,0x06,0x58,0x22,0x7D,0x65,0x9D,0x87,0x8B,0x5B,0xD7,0x53,0x67,0x37,0x96,0x21,0x79,0x6F,0x7D,0xEB,0xD5,0x64,0xB7,0x92,0x43,0x9B,0xC7,0x50,0xDD,0x92,0x1D,0xF7,0x9E,0x53,0xDF,0xDD,0x59,0xCB,0x21,0xAD,0xF6,0x46,0xA0,0x08,0xE5,0x2E,0x22,0x1B,0x40,0x01,0xDD,0xB2,0x2A,0xE0,0xB7,0x0C,0x03,0x4C,0x9D,0x4A,0x80,0xEA,0x54,0xFE,0x1F};
const uint8_t spLINE[] PROGMEM = {0x61,0xED,0x40,0xC7,0xCD,0xD2,0x96,0x65,0x01,0x9E,0x50,0x73,0x5B,0x96,0x83,0x70,0x87,0x2D,0xD9,0x9A,0x3B,0xA9,0x49,0x97,0x2E,0xB7,0xBF,0xDD,0x6D,0x4F,0x5B,0xD5,0xBA,0x95,0x75,0xD9,0xFD,0x1A,0x86,0x6B,0xD6,0x8A,0xC5,0x7B,0x9A,0xF3,0x3C,0xFA,0x51,0xAE,0x9E,0x59,0x55,0x2A,0x72,0xBE,0xC2,0x35,0x12,0xB9,0x88,0xBB,0x89,0x57,0xB8,0x7A,0x72,0x77,0xB0,0x3A,0xE9,0xEF,0x2E,0xC5,0xDD,0x1F,0x87,0xBF,0x8A,0xD0,0xEA,0x68,0xF8,0xFF};
const uint8_t spOFF[] PROGMEM = {0x6B,0x4A,0xE2,0xBA,0x8D,0xBC,0xED,0x66,0xD7,0xBB,0x9E,0xC3,0x98,0x93,0xB9,0x18,0xB2,0xDE,0x7D,0x73,0x67,0x88,0xDD,0xC5,0xF6,0x59,0x15,0x55,0x44,0x56,0x71,0x6B,0x06,0x74,0x53,0xA6,0x01,0x0D,0x68,0x80,0x03,0x1C,0xF8,0x7F};
const uint8_t spTIME[] PROGMEM = {0x0E,0xD8,0x5A,0x2D,0x00,0x37,0xA6,0x39,0xA0,0x9B,0xB0,0x95,0x17,0x9B,0x1E,0x21,0x2D,0x4F,0x51,0xF4,0x86,0x25,0x6F,0xB9,0xD5,0xA9,0xBB,0x9E,0xE0,0xD6,0x36,0xB7,0xBE,0xED,0x1E,0xD6,0xDC,0x5D,0x29,0xB7,0xAF,0xDE,0x6B,0xDD,0xCB,0xDE,0xB4,0xB1,0xAB,0xD6,0xC9,0x67,0x3C,0xDD,0x35,0x85,0x73,0x98,0xD8,0xFD,0x7F};
const uint8_t spAUTOMATIC[] PROGMEM = {0x6B,0xAC,0xA4,0xA7,0x82,0xFD,0xDD,0xF1,0x0E,0x67,0x68,0xB2,0xA2,0x83,0x72,0x1B,0xA0,0x52,0x65,0x03,0xFC,0x24,0x3A,0xEA,0xAD,0xCD,0xD5,0x4C,0xDB,0xA9,0xAB,0x76,0x4B,0x93,0x2D,0x67,0x28,0xA2,0xCC,0xC2,0xF3,0x8C,0x21,0x2B,0xD7,0x70,0xC9,0xD8,0x86,0x4A,0x8D,0xC6,0x35,0x49,0xE9,0x8B,0x54,0x29,0x76,0x37,0x63,0xC8,0xCE,0xDD,0x54,0x6A,0x9D,0xBA,0xC6,0xD2,0xD2,0x58,0x72,0xAB,0x5B,0xDE,0x72,0x35,0x35,0x5B,0x84,0x54,0x6D,0xD3,0xEE,0x90,0x11,0xEA,0x4E,0x5A,0x5B,0x53,0xAA,0xB3,0x2F,0xB9,0xD3,0x59,0xBB,0x6B,0xE5,0x94,0x35,0x7B,0x6F,0xE7,0x34,0xAD,0xD8,0xBA,0x17,0x81,0x22,0x94,0xBB,0x88,0x6C,0x00,0x03,0xB4,0x12,0x22,0x01,0x0E,0xFC,0x3F};
const uint8_t spWEIGHT[] PROGMEM = {0x62,0x13,0x7E,0x23,0x4C,0x22,0xEB,0x4D,0xAD,0x46,0x7F,0x5A,0xB0,0x95,0xB4,0x38,0xF3,0xA1,0x4E,0x6D,0xD6,0x94,0xCC,0x9A,0x3B,0x6D,0x39,0x7D,0xF3,0xC1,0x99,0xF2,0xE6,0xB4,0x23,0x0E,0x51,0xF8,0x9A,0xDB,0x8E,0x6E,0xE4,0x04,0xC9,0x7C,0xDC,0x17,0x75,0x8C,0x26,0xA8,0x56,0x8B,0x11,0x28,0x42,0xB9,0x8B,0xC8,0x06,0x00,0x00,0x01,0xBC,0xC0,0x66,0x80,0x1F,0x73,0x04,0xB0,0xDD,0x34,0x02,0x46,0xE9,0xF8,0x7F};
const uint8_t spSMOKE[] PROGMEM = {0x08,0xF8,0xBB,0x4D,0x02,0x0A,0x78,0x33,0xCC,0x03,0x1E,0x40,0x40,0x53,0x1A,0x22,0xC8,0x92,0x35,0x87,0x92,0xD4,0x74,0x95,0x99,0x55,0x7B,0x52,0xB7,0x5D,0xEE,0x72,0x57,0xAD,0xF7,0x6E,0xA2,0x84,0xFB,0xD6,0xD1,0x6D,0x4E,0x6E,0x84,0xA3,0x37,0x84,0x8B,0x50,0xEE,0x22,0xB2,0x01,0x80,0x01,0x75,0x14,0x7B,0x80,0x01,0x39,0x98,0xFC,0x3F};
const uint8_t spABORT[] PROGMEM = {0x63,0xC9,0xA6,0x2A,0x54,0xD7,0x9C,0xA5,0xF0,0xEC,0x0A,0xCA,0xBB,0x67,0xB6,0x1B,0xD9,0xA6,0xAA,0x59,0xE9,0x46,0x8E,0x20,0xC2,0x83,0x25,0x0B,0x39,0x1D,0x4D,0x4D,0x77,0x37,0x76,0x1A,0x55,0x54,0x53,0xA9,0x94,0x65,0x17,0xAB,0xC8,0xAC,0xDA,0x53,0xB9,0xEF,0x72,0x35,0x51,0x5E,0x58,0xAB,0xFE,0xD5,0x66,0xB5,0x12,0x23,0xFA,0xD7,0x94,0x63,0x53,0x95,0xF8,0x69,0x6B,0xEE,0x4E,0x51,0xE2,0x2F,0x6C,0xB9,0x13,0x57,0x59,0x7F,0x04,0x8A,0x50,0xEE,0x22,0xB2,0x01,0x1C,0xB0,0x9D,0xBA,0x03,0x7E,0x0F,0x53,0xC0,0x48,0x53,0x08,0x88,0xD2,0xEC,0xFF,0x01};
const uint8_t spCALL[] PROGMEM = {0x02,0x48,0xA5,0xD8,0x02,0x1A,0x18,0x71,0x16,0x15,0x95,0xA4,0x7A,0x65,0x95,0xD5,0x44,0x88,0xFB,0x5B,0xDC,0x62,0x95,0x49,0x4E,0xA7,0x49,0xB6,0x5D,0xED,0x76,0x76,0x73,0x9A,0x4B,0xD9,0x83,0xBD,0x2A,0xB4,0xCE,0xF5,0x0A,0x77,0x50,0xB9,0x25,0x92,0x25,0xDE,0xE1,0x49,0xC2,0x77,0x44,0x5D,0xFB,0xEF,0xFF,0x01};
const uint8_t spCYCLE[] PROGMEM = {0x08,0xF8,0xB3,0x5C,0x03,0x16,0xB0,0x80,0x06,0x56,0x55,0x64,0xB9,0xBB,0xB7,0x39,0x4D,0x71,0xA5,0x15,0xBA,0xF8,0x36,0xBB,0x19,0x75,0xCB,0x8A,0xED,0x35,0xB1,0xB7,0xAC,0x15,0xA1,0xDC,0x45,0x64,0x03,0x03,0xE2,0x10,0x2A,0x53,0x54,0xE3,0x69,0xDC,0x79,0xAD,0x1D,0x67,0x57,0xB0,0xB7,0x76,0x6C,0xAC,0xDD,0xC9,0xEC,0xDB,0xD5,0x70,0x4C,0x07,0x69,0xCD,0x8F,0x7B,0x13,0x9B,0x49,0xA1,0xBC,0xFE,0xFB,0x7F};
const uint8_t spDISPLAY[] PROGMEM = {0x04,0x88,0xD0,0x63,0x2C,0x53,0xB5,0xB1,0x52,0x9F,0x3B,0xDF,0x79,0x4F,0x65,0xF8,0xCE,0x5D,0x4D,0xB9,0x29,0xE0,0xCF,0x52,0x0B,0x78,0x40,0x03,0x08,0xC8,0xDC,0x15,0x40,0x02,0xA9,0x2D,0x4A,0x6A,0x45,0xEC,0xB5,0xB6,0xA0,0xCA,0x71,0x4C,0x73,0xEA,0xCA,0x3B,0xC2,0xA5,0xCB,0xAD,0x6E,0x75,0x9A,0xA6,0x93,0xAD,0x62,0xF3,0xED,0xEE,0xB4,0x96,0x1E,0x13,0x25,0x7D,0xF3,0xDE,0xFB,0xDE,0xCE,0xE6,0x15,0xA3,0x6A,0x55,0x7D,0xCA,0x3B,0x62,0x22,0x67,0x6C,0xCE,0xDF,0xFF,0x03};
const uint8_t spEQUAL[] PROGMEM = {0x6D,0x18,0x49,0x91,0xBC,0x17,0xEF,0x6E,0x15,0xA3,0x15,0xA2,0xE5,0x93,0x9D,0xB5,0x7C,0x6C,0x07,0xB6,0x7C,0x1C,0xF2,0x11,0x19,0xAC,0xB2,0x0E,0x02,0x45,0x28,0x77,0x11,0xD9,0x00,0x04,0xF0,0xA3,0x88,0x01,0xBE,0x65,0xB4,0x36,0xC8,0x8D,0x08,0xF4,0x33,0xBB,0x39,0xB4,0xB5,0xE2,0xAE,0x0E,0xF2,0xDB,0xD7,0x7A,0xA4,0x33,0xD3,0xEA,0x0E,0xF0,0x9B,0xCE,0xC8,0xAE,0x92,0x24,0x77,0xB8,0x33,0xF8,0x68,0xE6,0xD6,0xF1,0xFE,0x7F};
const uint8_t spFAST[] PROGMEM = {0x08,0x68,0xD6,0x55,0x02,0x0A,0x18,0x22,0x5D,0x02,0x1A,0x58,0x45,0x75,0xA3,0x5E,0xFA,0xE6,0x96,0xB7,0x39,0x6D,0xD3,0xA3,0xD6,0xBA,0xFA,0xF6,0x6B,0xAE,0xAE,0xA4,0xCA,0xEE,0xAC,0xAD,0x99,0xD1,0x28,0x5B,0x5C,0x8E,0xE2,0x4A,0x2B,0xFD,0x4E,0xBE,0xE2,0x85,0x80,0x25,0x5B,0x39,0xC0,0x80,0xDF,0x32,0x24,0xA0,0x01,0x0B,0x58,0x80,0x02,0xC0,0x80,0x3B,0x4C,0x14,0xF0,0xBC,0x38,0x03,0x96,0xDD,0xF9,0x7F};
const uint8_t spABOUT[] PROGMEM = {0x63,0xCF,0xA6,0x2A,0x54,0xD7,0xDC,0x6D,0xAD,0x85,0x67,0x57,0x50,0x5E,0x76,0x1A,0xD9,0xA6,0xAA,0x59,0xF9,0x26,0xB6,0x20,0xC2,0x83,0x25,0x0B,0x5B,0x1C,0x4D,0x4D,0x77,0x37,0xA1,0x6F,0xD4,0x45,0xCD,0xB2,0xAC,0xBE,0x98,0xCD,0x34,0xDD,0x72,0xDA,0xAA,0xDA,0x2B,0x79,0xCD,0x6D,0x6F,0x77,0xC7,0xBD,0x94,0x23,0xA4,0xCE,0x22,0xDB,0x15,0x8F,0xF0,0x45,0xEB,0x55,0xC2,0x79,0xC4,0x2F,0x42,0xB9,0x8B,0xC8,0x06,0x00,0x03,0x4C,0xA7,0xEE,0x80,0xD7,0x53,0x09,0x50,0x83,0xCB,0xFF,0x03};
const uint8_t spGO[] PROGMEM = {0x06,0x08,0xDA,0x75,0xB5,0x8D,0x87,0x4B,0x4B,0xBA,0x5B,0xDD,0xE2,0xE4,0x49,0x4E,0xA6,0x73,0xBE,0x9B,0xEF,0x62,0x37,0xBB,0x9B,0x4B,0xDB,0x82,0x1A,0x5F,0xC1,0x7C,0x79,0xF7,0xA7,0xBF,0xFE,0x1F};
const uint8_t spINCH[] PROGMEM = {0x23,0x1B,0xD6,0x48,0x2A,0x67,0x9F,0x76,0xC4,0x20,0x89,0xBC,0x7D,0xEB,0x53,0x8F,0x90,0xEC,0x12,0xB7,0x77,0xBB,0xC6,0xEE,0x55,0x92,0x6B,0x72,0x59,0xAA,0x82,0x28,0x4F,0x35,0xE9,0x68,0x0A,0xB9,0xD3,0x6D,0x93,0xA6,0x28,0xC8,0xB1,0xB0,0x85,0x40,0x11,0xCA,0x5D,0x44,0x36,0x00,0x02,0xD6,0xDC,0xD2,0x80,0x05,0x32,0xE0,0x01,0x0F,0x10,0xA0,0x26,0xA1,0xFF,0x07};
const uint8_t spLOW[] PROGMEM = {0x65,0xDF,0x98,0xA3,0x4A,0xB4,0xE5,0x65,0x4E,0xAB,0x9F,0xD4,0xA2,0x92,0xBC,0x9E,0xB6,0xF2,0xC8,0x71,0xEA,0x7B,0x9B,0xD5,0x24,0x5E,0x3D,0xCC,0x79,0x77,0x3B,0xFB,0xB9,0xF4,0xBD,0xEE,0xF5,0x0C,0x97,0x37,0x5D,0x0B,0x92,0xC7,0xDF,0xFE,0xFD,0x7F};
const uint8_t spMOTOR[] PROGMEM = {0x66,0xAA,0x8C,0x69,0x53,0x92,0xC4,0x2D,0x2F,0x6B,0x2A,0x74,0xDA,0x9D,0xB2,0xDD,0xF6,0x36,0xAB,0xCE,0x78,0xDA,0x9D,0xB2,0xD5,0x9A,0x01,0xDB,0x77,0x45,0xA0,0x75,0xC5,0xB8,0x71,0x59,0xDA,0x31,0xE5,0x6A,0x22,0x63,0xDE,0xDA,0x9A,0xBB,0xA3,0x75,0x68,0xAF,0x7B,0x3E,0xC3,0x9D,0x97,0x60,0x87,0xE6,0x8B,0x4F,0x78,0x4B,0x76,0xB2,0x09,0xAF,0xFE,0xFD,0x7F};
const uint8_t spOPEN[] PROGMEM = {0x61,0xCC,0xB8,0x7B,0x8C,0xB2,0xF5,0x61,0x8F,0xAB,0xA9,0x30,0xA7,0x83,0xBC,0xCD,0xBA,0x95,0x19,0x57,0x97,0xB1,0x6B,0xD2,0x58,0x12,0x31,0x11,0x89,0x01,0x01,0x2E,0x9A,0x48,0x60,0x94,0xC5,0x86,0xBB,0xC9,0xA6,0x35,0x36,0x95,0x1A,0xA6,0x7B,0xF6,0x3E,0x8E,0x26,0x42,0x3D,0x78,0xF1,0x3C,0xCB,0xD5,0x0D,0x71,0x78,0x24,0xAB,0x77,0xBA,0x47,0x12,0x73,0xB1,0xB8,0xF9,0xFE,0x7F};
const uint8_t spPERCENT[] PROGMEM = {0x02,0xC8,0xD9,0x5C,0x03,0x2D,0x8A,0xB1,0x30,0x46,0x52,0xAF,0xBA,0x86,0x26,0x1A,0xF6,0x77,0x9B,0xD3,0xD5,0x18,0x68,0x69,0x59,0x63,0xEF,0x80,0x5F,0x5A,0x2D,0x60,0x01,0x0B,0x68,0xC0,0x03,0xAB,0x6E,0xDE,0x25,0x2D,0x17,0xDF,0xFA,0x36,0xBB,0x1D,0x53,0xB1,0x6E,0x23,0x5D,0xA7,0x5D,0x23,0x92,0xB9,0xA7,0x62,0x7F,0x20,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0xA0,0x80,0xA5,0x33,0x0C,0xF0,0xB3,0x27,0x02,0x5A,0x4A,0xFD,0x7F};
const uint8_t spPROBE[] PROGMEM = {0x02,0xC8,0x29,0x5D,0x03,0x2E,0x0A,0x83,0xCB,0x5D,0x33,0xF7,0xFC,0x94,0xD1,0x96,0x57,0x71,0xF2,0x53,0x66,0xDE,0xE9,0x8D,0xDE,0x76,0x3D,0xDB,0x3E,0x95,0xDD,0xBB,0x8E,0x54,0xEA,0x13,0x0F,0x73,0x19,0x95,0x91,0x46,0x9E,0xD8,0x23,0x68,0x47,0x47,0x24,0xE1,0x1F,0xFF,0xC3,0xEF,0x4D,0x6A,0x99,0x25,0x49,0x67,0xF4,0x96,0x69,0xBA,0x24,0x5E,0xEE,0xAA,0x91,0x2B,0x59,0xD7,0xFE,0x3F};
const uint8_t spREADY[] PROGMEM = {0x6A,0xB4,0xD9,0x25,0x4A,0xE5,0xDB,0xD9,0x8D,0xB1,0xB2,0x45,0x9A,0xF6,0xD8,0x9F,0xAE,0x26,0xD7,0x30,0xED,0x72,0xDA,0x9E,0xCD,0x9C,0x6D,0xC9,0x6D,0x76,0xED,0xFA,0xE1,0x93,0x8D,0xAD,0x51,0x1F,0xC7,0xD8,0x13,0x8B,0x5A,0x3F,0x99,0x4B,0x39,0x7A,0x13,0xE2,0xE8,0x3B,0xF5,0xCA,0x77,0x7E,0xC2,0xDB,0x2B,0x8A,0xC7,0xD6,0xFA,0x7F};
const uint8_t spSET[] PROGMEM = {0x08,0xF8,0x35,0x95,0x03,0x02,0xF8,0xC5,0x58,0x03,0x16,0xB0,0xC0,0x2A,0xA6,0x08,0x13,0xD7,0xCE,0xA7,0xEC,0xAE,0xD5,0xCC,0xD6,0xDC,0xEA,0x54,0x35,0xA6,0xA4,0xE5,0x9A,0x3D,0xCC,0x25,0x2E,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x00,0x30,0x60,0x88,0x30,0x05,0xFC,0x1C,0x25,0x80,0x65,0xB6,0x10,0x50,0xA2,0xD0,0xFF,0x03};
const uint8_t spSPEED[] PROGMEM = {0x04,0xF8,0xBD,0x5C,0x02,0x1A,0xD0,0x80,0x04,0x30,0x40,0x00,0x6E,0x55,0x59,0xCB,0x75,0x7A,0x7A,0xA5,0x59,0xC5,0xC8,0x41,0x64,0xBA,0x66,0xE5,0x33,0x95,0x82,0xEB,0xD6,0x9B,0xEE,0x6C,0xE5,0x33,0x8D,0x82,0xEB,0xD6,0x5D,0xAD,0x7E,0xC5,0x22,0x48,0xDF,0xB2,0xC7,0xBD,0xCC,0x6D,0x1E,0xF5,0x60,0xA7,0x65,0x1E,0x95,0x91,0x88,0x9F,0xF4,0x2A,0xD7,0xD0,0x4D,0x64,0xBE,0xE5,0xFF,0x01};
const uint8_t spUNDER[] PROGMEM = {0xA7,0x6B,0xA4,0x3B,0x4A,0xB3,0x9C,0xAE,0xF1,0xF6,0x48,0xE9,0x7C,0xDB,0x55,0x56,0x13,0x56,0x62,0x8D,0x5B,0x56,0x15,0xFA,0x68,0x68,0xA9,0x79,0x28,0xA2,0xE0,0x31,0x4D,0x8D,0xA6,0x36,0x52,0x27,0x39,0x13,0x85,0x7E,0x7A,0x35,0x56,0x4D,0xB2,0xD6,0xE6,0x4D,0x55,0xAD,0xD5,0x58,0x6B,0x0E,0xB2,0x92,0x3C,0x73,0x2F,0x47,0xE9,0x4A,0x99,0xBC,0x25,0x9F,0xE1,0xCA,0x43,0xB0,0x53,0x7A,0x85,0xBB,0x1C,0xE1,0x56,0xCB,0xEC,0xEF,0xFF,0x07};
const uint8_t spOPERATOR[] PROGMEM = {0xB0,0x9A,0xAC,0xB6,0xC2,0xAD,0xCD,0xA9,0x3B,0x9D,0xCE,0x94,0x2C,0xB7,0x5A,0x65,0xB6,0x9B,0x61,0xBA,0x66,0x15,0xC5,0x65,0x8C,0xF3,0x62,0x94,0x89,0x50,0xEE,0x22,0xB2,0x01,0x5A,0x95,0x7C,0xB9,0xAB,0x25,0x29,0x55,0x5C,0xC2,0xD3,0x94,0xB5,0x37,0xA9,0x0B,0x9B,0x2C,0x4B,0xB9,0xE6,0xA1,0x8E,0x63,0xCE,0x83,0x53,0xD2,0xFC,0xAE,0xA5,0x16,0x97,0x70,0xCD,0x3B,0xD6,0x11,0x4F,0x30,0xB4,0x4F,0xDB,0x46,0x3C,0x62,0xE3,0x3D,0xF9,0x00,0x07,0xCC,0xD4,0x29,0x81,0xB6,0xD5,0x3A,0x28,0x2D,0x7E,0xDB,0x51,0xFD,0x09,0x2C,0xFB,0xCF,0x77,0x7A,0x4A,0x2C,0x94,0x93,0xBC,0xE1,0xA9,0xE1,0x04,0x46,0xFD,0xC5,0x37,0xFC,0x65,0x19,0x56,0x72,0x96,0xFF,0x07};
const uint8_t spAMPS[] PROGMEM = {0x69,0xEA,0xA5,0x45,0xD2,0x57,0xEF,0xF1,0x0E,0x77,0xB8,0xDD,0x6D,0x4F,0x53,0x43,0x49,0x79,0xCC,0xDE,0x5D,0x19,0x9B,0x08,0x2C,0x31,0xA7,0x6E,0x49,0x3C,0x39,0xC5,0xBC,0xEA,0x07,0x81,0x22,0x94,0xBB,0x88,0x6C,0x00,0x06,0x44,0x16,0xC6,0x80,0x5F,0xD3,0x39,0xC0,0x01,0x0E,0x50,0x00,0x03,0x18,0xF8,0x7F};
const uint8_t spMEGA[] PROGMEM = {0x66,0x31,0x3C,0x7C,0x52,0xE3,0xF8,0xC5,0xCF,0x6B,0x2A,0x5E,0x3C,0x34,0x96,0x9C,0xBE,0xC7,0x10,0x77,0x7F,0x7D,0x9B,0x51,0xF5,0xA1,0x6C,0xE2,0x8F,0x53,0xDD,0x1A,0x52,0x68,0x4D,0x0E,0x43,0xF5,0x48,0xE3,0x55,0xBA,0xCD,0x7D,0xA4,0x28,0x6B,0x93,0x35,0xB7,0xC2,0x12,0x9A,0x4F,0xCE,0x5A,0x5D,0x68,0xBA,0x6E,0xDE,0xDB,0x3C,0xC7,0x59,0xA2,0x66,0x6A,0xCC,0xE9,0x6F,0x7D,0xFF,0x1F};
const uint8_t spPICO[] PROGMEM = {0x08,0xC8,0x8E,0x48,0x03,0x2B,0xEA,0xC1,0x48,0xD2,0x57,0x9F,0x6C,0xE6,0x25,0x08,0x5B,0x73,0xB3,0x54,0x8C,0xC1,0xE0,0x56,0xB3,0x75,0x15,0x80,0xE6,0x47,0x3D,0x30,0x86,0xE2,0x82,0x35,0xB4,0xF7,0x1A,0xB2,0x71,0xF3,0xD6,0xBC,0x6B,0xA9,0xA2,0x2C,0x8A,0xBD,0x8F,0x23,0x89,0xF5,0x34,0xC9,0xDF,0xCF,0x76,0x45,0x57,0x51,0x22,0x79,0xD3,0xED,0xFD,0x6A,0xA8,0x75,0x8D,0x8F,0x79,0x6C,0xCD,0x74,0xB6,0xDD,0xEA,0xB5,0x65,0xD4,0xCD,0xFA,0xFC,0x3F};
const uint8_t spFIRE[] PROGMEM = {0x04,0x18,0xCE,0x4D,0x02,0x1A,0xD0,0x80,0x04,0x46,0x91,0x55,0x57,0x07,0x6D,0xD9,0xCD,0xAE,0x4F,0x55,0x5D,0x59,0x87,0xAE,0xB9,0xD5,0x6D,0x5B,0xDB,0x7D,0x93,0xB6,0xED,0xEE,0xE3,0x5A,0x6B,0x6A,0xF4,0x91,0xD5,0x73,0x6B,0x67,0xF5,0x47,0xBC,0xD4,0xA7,0x9C,0xA5,0x34,0xE4,0xD0,0xA6,0xF0,0xE4,0xAA,0xB8,0x2D,0xAB,0xC3,0x9B,0x62,0xC2,0xAC,0x74,0xF6,0x9F,0xFB,0x72,0x0B,0xEC,0x92,0xCD,0xEE,0xCF,0x43,0x69,0x4C,0x5B,0xFF,0x3F};
const uint8_t spPOWER[] PROGMEM = {0x0C,0xF0,0xDC,0x4C,0x03,0x2B,0xCD,0x36,0xAB,0x85,0x1B,0x9F,0xBC,0xB1,0xAE,0x6A,0xEA,0x7A,0xB3,0x95,0x15,0xD5,0x39,0x85,0x5D,0x46,0x96,0x7C,0x57,0x3B,0xB6,0x19,0x79,0x30,0x93,0x55,0xA4,0xBB,0xD4,0x2E,0xAD,0x79,0xB1,0xDE,0x3E,0x8D,0x29,0x85,0x61,0x1F,0xF6,0x3B,0xB7,0x7E,0x94,0x33,0x97,0x46,0x5B,0xCE,0x9D,0x9F,0xF0,0x16,0x3F,0x48,0xE7,0x7E,0xC3,0x5B,0xE3,0xA2,0xAC,0xEB,0xF6,0xDF,0xFF,0x03};
const uint8_t spCOMPLETE[] PROGMEM = {0x0E,0x68,0xA1,0x43,0x03,0xA7,0x2E,0xB2,0x22,0x0B,0xBB,0xDC,0x76,0x75,0x55,0x99,0xB7,0x53,0xB4,0xD1,0x77,0xA6,0x1C,0xA5,0xD6,0x7A,0x9F,0xFA,0x44,0x39,0x5A,0xDC,0x1E,0x9D,0x0C,0x50,0x94,0xB8,0x01,0x46,0x14,0x2F,0x69,0x97,0x9C,0x69,0xA6,0xE4,0x14,0x8D,0x85,0xBB,0x73,0xB3,0x93,0x75,0x6D,0xA2,0x29,0x6F,0x56,0xD6,0xB3,0xB2,0xA8,0x3F,0x59,0xF9,0x18,0x4E,0xA4,0xBE,0x66,0xB6,0x69,0x9F,0xB9,0x08,0xD2,0xDE,0xC4,0x1D,0x81,0x22,0x94,0xBB,0x88,0x6C,0x00,0x00,0x05,0x1C,0xD9,0x6E,0x80,0x65,0x7E,0x18,0xD0,0xEB,0x3A,0x02,0x6A,0x09,0xFC,0x7F};
const uint8_t spREPAIR[] PROGMEM = {0x69,0x8E,0x8D,0xCD,0x22,0x95,0xB7,0xA9,0x74,0x09,0xB2,0x54,0x7F,0xC6,0x16,0x83,0xCD,0xB5,0xEF,0x1A,0x7A,0x18,0x22,0x97,0xBE,0x75,0x62,0x93,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x04,0xE0,0x93,0x59,0xCB,0x92,0x53,0xCB,0x8C,0x9A,0xAB,0x68,0xD1,0xC5,0xC2,0x5E,0x9F,0xB2,0xA5,0x22,0x0F,0xD9,0x72,0xAB,0x5B,0xDF,0xE6,0x4E,0x63,0xA9,0x25,0xB0,0x4A,0x3B,0xCF,0xAD,0x1F,0xE9,0xAE,0x7A,0x85,0x4E,0xF2,0xE5,0x27,0xBF,0xF9,0xCD,0x5F,0xFA,0x4A,0x1C,0x92,0xE3,0xDC,0xE9,0x2B,0x35,0xA9,0x5A,0x72,0xFF,0x3F};
const uint8_t spTEMPERATURE[] PROGMEM = {0x0E,0xF8,0x2E,0x2C,0x00,0xCB,0x8F,0x8F,0xA8,0x59,0x15,0xF7,0x58,0x79,0xD2,0x9A,0x5D,0x22,0xB5,0xF5,0x4D,0x47,0x96,0xAB,0x5A,0x87,0x69,0x0E,0x85,0xF7,0x46,0x1D,0xA1,0x0C,0x10,0xE0,0x32,0xBB,0x04,0x56,0x5E,0x62,0x91,0xA6,0x79,0xEF,0x7D,0xEC,0xC1,0x00,0x63,0x6C,0x46,0xC0,0x03,0x16,0x18,0x7D,0x8F,0x29,0x68,0x96,0xB5,0x4D,0x25,0x27,0x71,0x85,0xF7,0xBE,0xF6,0xBD,0x9F,0xF5,0x09,0x77,0x59,0xC2,0xDE,0x9A,0x27,0xBE,0xFE,0xFD,0x7F};
const uint8_t spSTOP[] PROGMEM = {0x0C,0xF8,0xA5,0x4C,0x02,0x1A,0xD0,0x80,0x04,0x38,0x00,0x1A,0x58,0x59,0x95,0x13,0x51,0xDC,0xE7,0x16,0xB7,0x3A,0x75,0x95,0xE3,0x1D,0xB4,0xF9,0x8E,0x77,0xDD,0x7B,0x7F,0xD8,0x2E,0x42,0xB9,0x8B,0xC8,0x06,0x60,0x80,0x0B,0x16,0x18,0xF8,0x7F};
const uint8_t spMACHINE[] PROGMEM = {0xC2,0x56,0x3C,0x7D,0xDC,0x12,0xDB,0x3E,0x8C,0x89,0xBA,0x4C,0x4A,0x96,0xD3,0x75,0x95,0x12,0x6E,0xBD,0x6F,0xB7,0xBA,0x16,0x5A,0x58,0x3D,0xB3,0x03,0xA6,0x14,0x76,0xC0,0xCC,0x37,0x11,0xC8,0x40,0x04,0x22,0xB0,0x92,0xD9,0x9A,0xC1,0x7D,0xF5,0xCD,0x6F,0x3E,0x8A,0x39,0x14,0xA5,0x72,0xD4,0x28,0x67,0x56,0xD4,0x89,0xD2,0xB3,0xE9,0x63,0x5D,0xD2,0xDA,0x03,0x49,0xA9,0xDB,0xCD,0x47,0x3C,0xE3,0xEB,0xBF,0xF4,0x75,0x57,0xEC,0xEE,0x9B,0xF2,0x9B,0xBE,0x56,0x34,0xCC,0xA2,0xF2,0xFF,0x03};
const uint8_t spON[] PROGMEM = {0x65,0x4A,0xEA,0x3A,0x5C,0xB2,0xCE,0x6E,0x57,0xA7,0x48,0xE6,0xD2,0x5D,0xBB,0xEC,0x62,0x17,0xBB,0xDE,0x7D,0x9F,0xDA,0x5C,0x5C,0x7A,0xAA,0xB5,0x6E,0xCB,0xD0,0x0E,0xAD,0x6E,0xAF,0xEE,0xF9,0x88,0x67,0xBC,0xDC,0x3D,0xAC,0x60,0xB8,0x45,0xF3,0xB7,0xBF,0xC3,0xDD,0xA2,0xBB,0xAB,0xCD,0x89,0x8F,0x7F,0xFE,0x1F};
const uint8_t spCONTROL[] PROGMEM = {0x06,0x68,0xA5,0xCD,0x02,0x2B,0xA9,0x36,0xD5,0x43,0x5A,0x9F,0xA6,0xA9,0x36,0x4F,0xEE,0x73,0xDA,0xC1,0xDA,0x35,0x79,0x73,0x6B,0x9B,0x62,0xEA,0xB0,0x78,0xB3,0x4B,0x7D,0x91,0x18,0xED,0xE6,0x16,0x81,0x22,0x94,0xBB,0x88,0x6C,0x10,0x40,0x0B,0xE1,0x1E,0x88,0xC0,0x48,0x53,0xE2,0x0A,0x17,0x67,0x3B,0x3B,0x59,0xB2,0x11,0x95,0xA2,0x7C,0x64,0x91,0x4F,0x47,0x92,0xF7,0x99,0xAF,0xA2,0xE0,0xEE,0x76,0x56,0xBF,0x9B,0x39,0xB4,0x29,0xB1,0x9C,0x76,0xF4,0x56,0xD7,0xBA,0xE5,0x3B,0x3F,0xF1,0x29,0x77,0xE6,0x9D,0x63,0x9C,0xE7,0xFF,0x01};
const uint8_t spELECTRICIAN[] PROGMEM = {0x6B,0x9D,0xA6,0x88,0xD3,0x36,0xDF,0xF1,0x8C,0x5B,0x84,0x93,0x79,0xBB,0x35,0x5C,0x26,0xA9,0xEC,0x6B,0xCF,0x70,0xB8,0x87,0xBA,0x68,0x3F,0x5D,0x4B,0xA1,0x29,0xB6,0xF9,0xB6,0xAD,0x69,0xB1,0x48,0x5B,0x1B,0x23,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x06,0x38,0xAE,0xD2,0x03,0xA3,0xAC,0x59,0x4D,0xDD,0x9D,0xAE,0xA2,0x16,0x63,0x37,0xEB,0xBA,0x8B,0x51,0x36,0x63,0x1A,0x9E,0x6B,0x7A,0x65,0x80,0x55,0xB7,0x3D,0x10,0x81,0x0C,0x58,0x60,0x75,0xCD,0x98,0x84,0xF9,0xA6,0xBD,0xF4,0xAD,0x5C,0x43,0x19,0x46,0x58,0xB4,0x7C,0xE7,0x27,0x7D,0x3D,0x0A,0xBB,0x87,0xDD,0xF8,0xC7,0xFF,0xFF,0x01};
const uint8_t spAT[] PROGMEM = {0xAD,0xA8,0xC9,0xB5,0xBC,0xA6,0xDC,0xFE,0x36,0xB7,0xB9,0xF5,0x6D,0xC7,0x58,0x9B,0x69,0xF9,0x4C,0x99,0x73,0xDD,0xC8,0x24,0x42,0xB9,0x8B,0xC8,0x06,0x00,0x50,0xC0,0x52,0x2E,0x0E,0xB8,0x66,0x8A,0x01,0xAD,0x95,0x20,0x20,0x3A,0xF2,0xFF,0x07};
const uint8_t spRED[] PROGMEM = {0x6A,0xB5,0xD9,0x25,0x4A,0xE5,0xDB,0xC5,0x4F,0x6D,0x88,0x95,0x2D,0xD2,0xB4,0x8F,0x2E,0x37,0x0E,0x33,0xCF,0x7E,0xAA,0x9A,0x5C,0xC3,0xB4,0xCB,0xA9,0x86,0x69,0x76,0xD3,0x37,0xB7,0xBE,0xCD,0xED,0xEF,0xB4,0xB7,0xB0,0x35,0x69,0x94,0x22,0x6D,0x10,0x28,0x42,0xB9,0x8B,0xC8,0x06,0x00,0x50,0xCF,0x0E,0xEE,0x62,0xEA,0xA6,0xBC,0xC3,0x14,0xBB,0x4A,0x9F,0xFA,0xA5,0xAF,0x25,0x13,0x17,0xDF,0x9C,0xBF,0xFF,0x07};
const uint8_t spALL[] PROGMEM = {0x65,0x0D,0xFA,0x3B,0x84,0xFB,0x8D,0x2E,0xB1,0x9D,0x34,0xCA,0xBA,0xAB,0x5D,0xEC,0x62,0x15,0x89,0x5F,0xA7,0x49,0xB6,0x5D,0xEF,0x6E,0x0E,0x73,0x99,0xEB,0x3C,0xCA,0x11,0x65,0xCE,0x18,0xB9,0x89,0x67,0xBC,0xDC,0x15,0xF8,0xE5,0xA0,0xE6,0x71,0x77,0x94,0x51,0x8F,0x96,0xE6,0xFF,0x01};
const uint8_t spCANCEL[] PROGMEM = {0x01,0x98,0x29,0xC4,0x00,0xDD,0x29,0x9C,0xAC,0x25,0xD7,0xD2,0x9C,0x7C,0x8B,0x5B,0xAE,0xBC,0x26,0xB3,0x94,0x89,0x52,0xF2,0xE6,0x29,0x42,0x52,0x53,0x28,0xAA,0xC1,0xB6,0xB0,0xC4,0x0C,0xF8,0xDE,0xC2,0x02,0x1E,0xF0,0x80,0x05,0x46,0x5C,0x78,0x45,0x25,0xE5,0x19,0x53,0x45,0x93,0xE3,0xA2,0x77,0xAE,0x75,0x4B,0x67,0x92,0xD5,0x6D,0x98,0x25,0x3F,0xF9,0xFD,0x7F};
const uint8_t spPHASE[] PROGMEM = {0x22,0x5E,0x2E,0xD5,0xC4,0x64,0xA5,0xF6,0x9A,0x52,0x26,0xF1,0xB6,0xDA,0xEA,0x54,0x2C,0x6B,0xCE,0x69,0x7A,0x0A,0x51,0x89,0xB7,0xA7,0x19,0xA9,0x98,0xCD,0xDE,0xDC,0xE6,0x36,0xAB,0x9B,0xA1,0x11,0x23,0x3E,0xCF,0xB1,0xAF,0x7D,0xAB,0x7B,0x3C,0xFC,0x19,0x9E,0xA6,0x55,0x9C,0x6D,0xB7,0x7F,0xEC,0xCB,0x80,0xEF,0xCB,0x39,0x40,0x81,0xFF,0x07};
const uint8_t spNOR[] PROGMEM = {0xE9,0x38,0x5C,0x84,0x33,0xBD,0x8E,0xB6,0x9A,0x70,0x09,0x6B,0xBB,0x8B,0x93,0x66,0xDE,0x91,0xC9,0xFE,0x6E,0xBA,0xB2,0x24,0xAA,0x26,0x51,0xDD,0xCC,0x47,0x1D,0x7C,0x75,0x3A,0xE5,0x99,0xC3,0x5C,0xCA,0x1E,0x52,0x6A,0xA7,0xE4,0xCF,0x7B,0xB9,0x53,0x4E,0x8E,0x31,0x6F,0xFD,0x4C,0x77,0x1A,0xC2,0x93,0x96,0x25,0xDD,0xA9,0x04,0x4E,0x87,0xDB,0xF0,0xE4,0x2D,0xB4,0x6E,0x59,0xE2,0xE3,0xDF,0xFF,0x07};
const uint8_t spEXIT[] PROGMEM = {0x6B,0x68,0xC1,0x24,0xAD,0xEE,0xAC,0xA6,0xE7,0x66,0x57,0x7F,0x73,0x9B,0x5B,0xB6,0xA2,0x1F,0x56,0xC5,0x69,0x6A,0xDA,0x96,0x94,0x02,0xB2,0x89,0x02,0x9A,0x1C,0x35,0xC0,0xCF,0x99,0x16,0xB0,0x80,0x04,0xDA,0x5C,0x83,0x4A,0xF0,0xDC,0x5E,0x5B,0x33,0x49,0xA1,0xFE,0xB9,0x9F,0xE1,0x6B,0x41,0x39,0xD8,0x1E,0x23,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x02,0x38,0xCC,0xDC,0x02,0x04,0x18,0xF6,0xF3,0xFF,0x01};
const uint8_t spFLOW[] PROGMEM = {0x04,0xE8,0x3E,0x83,0x02,0x1C,0xE0,0x80,0x04,0x3C,0x10,0xB2,0x24,0x75,0xD9,0xAC,0x4D,0xCD,0x5A,0x9D,0x85,0xAC,0x93,0x79,0x39,0x75,0xA3,0xDE,0x15,0x98,0xED,0x56,0xB7,0x5A,0x55,0xE2,0xD3,0xE9,0xE4,0x6F,0xD6,0xB3,0x9B,0x43,0x5F,0xEB,0x91,0x4F,0x77,0x5B,0xBB,0x15,0xC2,0x7E,0xFC,0x63,0x5E,0x1B,0xD7,0x0B,0xA5,0xB7,0x7E,0xFF,0x1F};
const uint8_t spGAUGE[] PROGMEM = {0x0E,0x18,0xD5,0xB0,0xB5,0x2B,0x24,0x09,0x7B,0x92,0x55,0xF7,0x4C,0xA2,0xD1,0x8D,0x6F,0x7D,0x9A,0x91,0x83,0x34,0x72,0xCE,0x6D,0x6E,0x73,0xDB,0xD5,0xCD,0x50,0x40,0x9D,0xAB,0xF7,0xB8,0xE7,0xBD,0xB5,0x7D,0xA5,0x46,0x8C,0x58,0x5D,0x0F,0x76,0x15,0x05,0xBE,0x96,0x8D,0xD8,0x59,0x0D,0xE8,0x58,0xD5,0xA2,0x97,0x7A,0xC6,0x72,0x17,0x31,0x5B,0xB2,0x65,0xC0,0x9A,0xCE,0x12,0xB0,0x80,0x02,0xE6,0x50,0xF9,0x7F};
const uint8_t spGREEN[] PROGMEM = {0xE1,0x6A,0xEA,0x2A,0x4A,0xE3,0xA6,0xA1,0xB8,0x49,0x32,0x51,0x9A,0xFA,0xE8,0xCC,0xAC,0x2C,0x59,0xED,0x5A,0x5B,0x3A,0x05,0x27,0x77,0x9D,0xF5,0x29,0xDA,0x70,0x91,0x90,0xB6,0xA7,0x18,0x35,0x90,0xD3,0x17,0xED,0x7C,0xE5,0x33,0x06,0xE2,0x54,0xA5,0x5D,0xCC,0xAA,0xF5,0xB3,0x07,0x50,0xD6,0xA8,0x36,0x8E,0xA0,0x68,0x6B,0x61,0xFA,0x52,0xB7,0xB2,0x8F,0x44,0x54,0x15,0x41,0xD2,0x31,0x12,0x86,0xB8,0xBB,0xCE,0x67,0xBA,0xAA,0x66,0x4B,0xF1,0xB8,0xE9,0xEA,0x91,0x43,0xCC,0x5C,0xC7,0x33,0x5E,0xE5,0x6A,0xD6,0x25,0xDC,0x67,0xA5,0xA7,0x55,0x0D,0xD5,0x98,0x9C,0xDF,0xFF,0x07};
const uint8_t spINSPECTOR[] PROGMEM = {0x29,0xEB,0x5E,0xD9,0x32,0x27,0x9D,0x6E,0xFA,0x66,0x17,0x59,0x7D,0xDB,0xDB,0xB4,0xB6,0x7B,0xD0,0xCC,0x70,0xD2,0xDB,0xD6,0x0D,0xC7,0x38,0xAC,0x4D,0xD2,0xF0,0x0D,0xB3,0xA9,0xBB,0x73,0xC0,0x4F,0xE9,0x11,0xF0,0x80,0x02,0x86,0x52,0x01,0x03,0x44,0xEA,0x7A,0xA2,0x1A,0x43,0xD3,0x6C,0xF3,0x4D,0x6F,0xDA,0xB2,0x56,0x0C,0x82,0xAD,0x31,0x29,0x44,0x28,0x77,0x11,0xD9,0x00,0xE0,0x80,0xED,0x3C,0x46,0x5F,0xEB,0xA0,0xB4,0xF8,0x2D,0x53,0xF5,0x27,0xB0,0xEC,0x3F,0x6F,0x69,0x2F,0xB1,0x50,0x4E,0xF2,0x86,0xB3,0x86,0x13,0x18,0xF5,0x17,0xDF,0xF0,0x96,0x65,0x58,0xC9,0x59,0xFC,0xF7,0xFF};
const uint8_t spMANUAL[] PROGMEM = {0x6E,0x8A,0x42,0x6C,0xD5,0x9A,0xA4,0xB1,0x72,0xA5,0x2A,0x49,0x5B,0x87,0xD3,0x75,0x5B,0x1A,0x2E,0xAB,0x6F,0x7D,0xAB,0x53,0x76,0xDF,0x12,0xE6,0xAF,0x6F,0x71,0x8A,0x1E,0x43,0x52,0x72,0xF1,0x2A,0x7A,0x24,0x4D,0x4E,0xD7,0xA5,0x6A,0x06,0x32,0x2D,0x34,0x8F,0x7A,0x24,0x12,0x97,0x4E,0xB8,0xFA,0xE1,0x1D,0xD5,0xB3,0xE1,0x1A,0x7A,0x0D,0x12,0xB5,0xD5,0x6B,0xAC,0x51,0x24,0xD4,0x56,0x97,0x25,0x5A,0xB3,0x32,0x59,0x93,0xB6,0xA8,0x27,0x3C,0x31,0x4F,0xDE,0xEB,0x5E,0xCF,0x72,0x26,0x3E,0xD5,0xC6,0xF9,0xCA,0x55,0x71,0x77,0x39,0x7B,0x2B,0xD7,0x40,0xD1,0x1D,0xAC,0xBD,0xDC,0x05,0x57,0x77,0x90,0xB7,0xFC,0xFC,0x3F};
const uint8_t spMOVE[] PROGMEM = {0x6A,0xD7,0xC2,0xF2,0xD2,0xEC,0xB8,0x39,0x08,0xF6,0x4D,0x4D,0x1A,0xC6,0x24,0x31,0xB2,0xCC,0x69,0x1E,0x56,0x9D,0x85,0x7B,0x15,0xA4,0x3B,0x55,0x23,0x9E,0x3E,0xE0,0x6D,0xE7,0x23,0xAF,0x20,0xC6,0x0A,0xBC,0xCE,0xA2,0x34,0x91,0x6C,0x89,0x43,0xDF,0x3A,0x94,0x31,0x83,0x6E,0x4D,0xE8,0x9A,0x96,0x0C,0x3A,0x63,0x20,0x5B,0xD8,0xAC,0xEC,0xC8,0x20,0x37,0x7E,0xB7,0xA7,0x3D,0xCD,0xD9,0x8A,0x78,0x28,0x2E,0xB5,0x97,0xBD,0xED,0xCD,0x80,0x52,0x32,0x28,0x80,0x81,0xFF,0x07};
const uint8_t spOVER[] PROGMEM = {0x63,0x6F,0xC4,0x7A,0x1D,0xB5,0xED,0x61,0x37,0xBB,0x6E,0x75,0x62,0xD9,0x2D,0xEC,0xBF,0x56,0xAD,0x09,0xBA,0x32,0x8C,0x13,0xC7,0xD6,0xED,0x4D,0x85,0x86,0x99,0xE3,0x3E,0xB7,0x29,0x86,0x90,0x2C,0x76,0xDB,0xE6,0x98,0x95,0xBB,0x38,0x4F,0x5B,0x72,0x29,0xB4,0x51,0x6F,0x7D,0xAF,0x47,0xB9,0x73,0x71,0x8C,0x31,0x3F,0xE1,0xC9,0xA9,0x50,0xD6,0xFD,0xBA,0x27,0x57,0xC5,0x6E,0xCD,0xFD,0xFF};
const uint8_t spPLUS[] PROGMEM = {0x0A,0x18,0x4D,0x44,0x01,0x23,0x70,0x12,0x40,0x8B,0xD8,0x92,0x7A,0xD3,0x63,0x10,0xAD,0x57,0x91,0xC4,0xB5,0x8A,0xAE,0x39,0x45,0xE1,0x93,0xE9,0xBC,0xE5,0x96,0xB7,0x59,0x43,0x15,0x63,0xE9,0xBA,0x6B,0x6E,0xF5,0x64,0x40,0xF0,0xEE,0x0A,0xF8,0x25,0x43,0x03,0x1E,0xD0,0x80,0x04,0x38,0x40,0x01,0x0C,0xFC,0x3F};
const uint8_t spPULL[] PROGMEM = {0x06,0xF0,0xB6,0x9C,0x01,0x2C,0xB7,0x8F,0x28,0xCA,0x1E,0x53,0x5A,0xBA,0x93,0x95,0x0C,0x2C,0xD3,0x81,0xDA,0x76,0xBA,0xB3,0x51,0x57,0x14,0xB3,0x8E,0xEE,0x67,0xDF,0x87,0x34,0x17,0xE2,0x3B,0x86,0x5E,0xEB,0x11,0xCE,0x24,0x62,0xD3,0xB0,0x69,0xBE,0xFD,0xE3,0xDE,0x20,0x67,0x54,0xA5,0xCD,0xFF,0x03};
const uint8_t spREPEAT[] PROGMEM = {0x6E,0xF1,0x49,0x42,0x33,0xD8,0xC5,0xB9,0x8C,0xB9,0x62,0x8A,0x87,0xF6,0xD3,0xB7,0xCC,0xC6,0x1A,0xE9,0x4E,0x33,0x9C,0x23,0x79,0x7C,0xDE,0x4D,0x6B,0x5B,0x62,0xB0,0xF4,0x95,0x64,0x16,0xA1,0xDC,0x45,0x64,0x03,0x04,0xA0,0xB5,0x94,0x96,0xF6,0x14,0x4C,0x62,0xAF,0x4E,0xD6,0x13,0x93,0x66,0xCD,0x3E,0xD9,0x6C,0x89,0x64,0xB1,0xFA,0x66,0xBB,0x18,0xFD,0xAC,0x0A,0x92,0xB5,0xA8,0xAD,0xA3,0x10,0x8B,0x4D,0x6D,0x7B,0x21,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x06,0xB8,0xDC,0xCD,0x01,0x33,0x6C,0x62,0x00,0x03,0xFF,0x0F};
const uint8_t spSHUT[] PROGMEM = {0x04,0x58,0xE3,0x5A,0x03,0x16,0xF0,0x80,0x07,0x22,0x60,0x81,0x55,0xB4,0xE4,0xA2,0x61,0x5D,0x6E,0x71,0xCA,0x12,0x3C,0xCA,0x7C,0xCE,0xAD,0x76,0x31,0xD7,0xBC,0x23,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x06,0xE8,0x44,0x5D,0x01,0x3F,0x66,0x11,0xE0,0x98,0x59,0x04,0xF4,0x38,0xFE,0xFF};
const uint8_t spTEST[] PROGMEM = {0x0E,0x98,0x6A,0xC9,0x00,0x2B,0x37,0xAF,0xA4,0x45,0x91,0xB0,0x5A,0x72,0xEA,0x9A,0x9D,0x23,0xE3,0xCD,0x6D,0x56,0x57,0x93,0x5A,0x78,0x2D,0xD9,0xE3,0x9E,0xEB,0x4E,0x77,0x02,0x6C,0x95,0x4A,0x80,0xDF,0xD2,0x39,0xA0,0x01,0x0D,0x48,0x80,0x01,0x4F,0x2B,0x53,0x00,0x14,0x70,0x45,0x9A,0x06,0x10,0x50,0x73,0xC3,0xFF,0x03};
const uint8_t spVOLTS[] PROGMEM = {0xA0,0xDA,0xA2,0xB2,0x3A,0x44,0x55,0x9C,0xFA,0xB0,0xBA,0x46,0x72,0xDA,0xD1,0xDB,0xAE,0x47,0x59,0x61,0xED,0x28,0x79,0xED,0x45,0xAF,0x5A,0xDF,0x60,0xF4,0x39,0x69,0xAB,0x63,0xD9,0x3B,0xD2,0xBC,0x24,0xA5,0xF5,0xB6,0x0F,0x80,0x01,0x3E,0x63,0x65,0xC0,0x5F,0x63,0x12,0x90,0x80,0x06,0x24,0x20,0x01,0x0E,0xFC,0x3F};
const uint8_t spGALLONS[] PROGMEM = {0x0E,0x28,0x8A,0xE5,0xB4,0xAD,0x04,0x9B,0xF9,0x9A,0x5B,0x9F,0xBA,0xE9,0x91,0x4A,0x5D,0x7D,0xAB,0x53,0x15,0x35,0xBE,0xA2,0x8B,0x77,0x35,0xEA,0xCC,0xC6,0x4F,0xA9,0x6E,0x6B,0x07,0xC8,0xEC,0x45,0xCF,0x6B,0x2C,0xA2,0x7C,0x4D,0x36,0xCF,0x65,0xAC,0x8D,0x97,0xB6,0xE9,0xE2,0x7A,0x86,0x7B,0x44,0xD4,0xB0,0x54,0x1A,0xEE,0xA6,0x51,0x32,0xC2,0xA9,0x7F,0xCC,0xD3,0x2D,0xA3,0xA7,0xC4,0xB7,0xAF,0x7E,0xE4,0xE7,0xBE,0xAF,0x4D,0x54,0x53,0x19,0x03,0xBE,0x60,0x62,0xC0,0xAF,0xAE,0x12,0x90,0x00,0x02,0x6A,0x70,0xFE,0x7F};
const uint8_t spHERTZ[] PROGMEM = {0x04,0xC8,0xA1,0xD8,0x02,0x1E,0x58,0x71,0x2E,0x81,0x31,0xDC,0x65,0x25,0xD5,0x9E,0xC2,0x9A,0xFE,0x9D,0xED,0x7A,0x8E,0x61,0xAD,0x25,0xC1,0x4A,0xF3,0x01,0x00,0x02,0xB6,0x09,0x65,0xC0,0x6F,0x65,0x1C,0xB0,0x80,0x05,0x34,0xE0,0x01,0x0D,0x10,0xA0,0x09,0x97,0xFF,0x07};
const uint8_t spMICRO[] PROGMEM = {0x22,0x8B,0x44,0xF5,0x92,0x9B,0xDA,0xC5,0xCF,0x6B,0xA8,0xBC,0x2B,0x8B,0xB3,0xDC,0xEE,0xB6,0xA7,0x6E,0x3E,0xB9,0xC2,0x56,0x9F,0xA2,0x57,0x93,0xD0,0x9C,0x5D,0x8A,0x3E,0x88,0x52,0xA6,0x32,0x2B,0xAA,0x15,0x34,0xCB,0xD4,0xC0,0x80,0x12,0x23,0x22,0x60,0x81,0x30,0xC5,0xAA,0x61,0x25,0xF9,0x7A,0xDF,0x87,0x31,0x17,0xDE,0x1E,0xC5,0xFE,0xDB,0x96,0xD5,0xD8,0x38,0xF4,0xAB,0x47,0x78,0xBC,0xAB,0x18,0xE1,0x3C,0xFE,0xF5,0xDF,0xFF,0x03};
const uint8_t spOHMS[] PROGMEM = {0xAD,0xC9,0x74,0x37,0x59,0xD2,0xED,0xE6,0xD4,0x95,0xF8,0x56,0xB0,0xD2,0x5D,0x9D,0xAA,0x12,0xAF,0x2D,0xB7,0xBA,0xDB,0xDE,0xB7,0x79,0x68,0x93,0x32,0x96,0xD2,0x97,0xBA,0xE6,0x3D,0x9F,0xEE,0x6A,0x92,0xB9,0x22,0x9C,0x98,0x2B,0x33,0x8E,0x16,0x8F,0xEB,0xEE,0x6E,0xD1,0x5A,0x3C,0x4D,0xB8,0x06,0x09,0x35,0xA5,0xDE,0xE1,0xFA,0xC5,0xD8,0x4D,0xE4,0x2A,0xE0,0x5B,0x15,0x05,0x7C,0x27,0xA4,0x01,0x0E,0x70,0x00,0x01,0xDE,0x6C,0xFE,0x3F};
const uint8_t spAREA[] PROGMEM = {0x2D,0xEF,0xA1,0xC8,0x32,0x36,0xDF,0xE5,0x0C,0xDD,0x0D,0xCB,0x68,0xDF,0xDB,0xAC,0xBA,0x0C,0xB1,0x32,0xED,0x3A,0xAA,0xD4,0x39,0x2C,0x4D,0xEF,0xAC,0x67,0xB3,0xFA,0xD2,0x58,0xD3,0x3D,0xEF,0x1A,0xBA,0x2B,0xD0,0xF2,0xDD,0x73,0x1E,0x4B,0xF7,0x89,0xE6,0xF1,0x79,0xAF,0x63,0xED,0x3E,0xD8,0xDD,0x3E,0x8F,0xAD,0x3A,0xF7,0x76,0x5D,0xD3,0xB7,0xBE,0xB7,0xBB,0xE9,0xB4,0x4E,0xE9,0x5D,0x3F,0xF7,0xA7,0x1C,0x9E,0xEA,0x4B,0xFE,0x1F};
const uint8_t spCIRCUIT[] PROGMEM = {0x02,0x78,0x2D,0x55,0x02,0x12,0xB0,0x80,0x01,0x5E,0x49,0x5D,0x49,0x35,0xAE,0x1A,0xD6,0xF6,0x94,0x25,0x05,0x5B,0x4A,0xD7,0x55,0x94,0x3C,0x28,0x2D,0xFE,0x76,0x11,0xCA,0xEA,0x06,0x25,0x35,0x29,0x02,0x45,0x28,0x77,0x11,0xD9,0x08,0x28,0x4E,0x15,0x1C,0x50,0x1C,0xD3,0xEA,0x6A,0x14,0x49,0xF7,0x4D,0x7B,0x19,0x67,0x53,0x45,0x65,0xB1,0xA7,0x3E,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x80,0x00,0x96,0x56,0x53,0xC0,0x1F,0xAD,0x02,0x78,0xAE,0x06,0x01,0xCB,0xB7,0xFF,0x3F};
const uint8_t spCONNECT[] PROGMEM = {0x06,0xA8,0xD5,0x29,0x24,0x3D,0xAC,0xB3,0x52,0xE6,0x55,0x97,0xA0,0x56,0x12,0x8D,0x4F,0xDB,0x9C,0x6A,0x4B,0x2C,0x2D,0xDD,0xC8,0xA8,0xEE,0xE9,0xB4,0xF6,0xAB,0x6B,0x4E,0xB5,0x28,0x93,0xAC,0xB6,0xC5,0x66,0x4F,0xDB,0x7C,0xBB,0xDB,0xEF,0x69,0x9E,0xE5,0x69,0xA1,0x39,0x3C,0x96,0x20,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x20,0x80,0xA5,0xC3,0x1C,0xB0,0xEC,0x97,0x05,0x18,0xD0,0xCB,0xDA,0xFF,0x03};
const uint8_t spSECONDS[] PROGMEM = {0x04,0xF8,0xC5,0x51,0x01,0xBF,0xA6,0x6A,0x40,0x03,0x16,0xD0,0xC0,0xCA,0xAB,0x75,0x2D,0xCD,0x25,0x37,0xBB,0xD9,0xCA,0xDA,0x54,0x0F,0xEE,0xD9,0x29,0x6B,0x47,0x30,0xD8,0xE3,0x80,0x00,0x6A,0x26,0x6D,0x55,0xEB,0xCA,0x21,0xB9,0xE4,0xD4,0xDD,0x26,0xA5,0xF9,0xE3,0x3D,0xB6,0x75,0x38,0xA3,0x31,0x5B,0x9A,0xB6,0x11,0x51,0x32,0xD2,0xAA,0x3F,0xFC,0x21,0xCE,0x22,0xD1,0xD7,0x2D,0x9E,0x39,0x0B,0x37,0x4E,0xD7,0x26,0xE1,0xFA,0xC4,0x55,0x42,0xFD,0x85,0xFB,0x7B,0x77,0x13,0xA3,0x27,0x80,0x03,0xD0,0x25,0x20,0x01,0x0A,0x20,0x20,0x69,0xD6,0xFF,0x07};
const uint8_t spUNIT[] PROGMEM = {0x61,0xB9,0x96,0x84,0xB9,0x56,0xE5,0xB9,0xCE,0x63,0xDE,0xCE,0x0D,0x30,0x36,0x9F,0x6E,0x86,0x36,0x60,0xE9,0x7B,0xCA,0x5E,0x93,0x45,0xA4,0xEB,0xC9,0xBB,0x77,0x72,0xE7,0x2D,0x2B,0xAB,0xD6,0x24,0x94,0x17,0x8F,0xA2,0x79,0x4C,0xD5,0x48,0x5D,0xAA,0xEE,0x21,0x23,0x42,0xF1,0x1A,0x66,0x54,0x15,0x97,0xD6,0x6B,0x19,0xD1,0xC5,0xC5,0x77,0xEF,0xB3,0x9F,0x7E,0x47,0xA0,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x01,0xCB,0xBB,0x3B,0xE0,0xD7,0x0A,0x05,0x9C,0xD0,0x4D,0x80,0xE6,0x92,0xFE,0x1F};
const uint8_t spTIMER[] PROGMEM = {0x0E,0xB8,0x36,0xC3,0x01,0xCD,0x98,0xB4,0x38,0x87,0x8C,0x0A,0x59,0x72,0x8B,0x5B,0x9D,0xAA,0x15,0x35,0x0B,0x9F,0x7D,0x8B,0x5D,0xB4,0xAA,0x78,0x96,0xB4,0xB0,0x5B,0xFB,0x32,0xE7,0xE8,0x9C,0x85,0x6D,0xDA,0x96,0xC3,0x10,0x9F,0x78,0x49,0x67,0x35,0xA7,0xF0,0xA6,0x2F,0xDD,0x39,0x2D,0xF2,0x89,0x9F,0xFC,0xC4,0xD7,0xFD,0xC5,0x1F,0xC3,0xBA,0x3F,0xF3,0x97,0x6D,0x54,0xC9,0xFD,0xFE,0x1F};
const uint8_t spUP[] PROGMEM = {0x2D,0xCD,0x72,0xA2,0x55,0x77,0xDD,0xF6,0x36,0xB7,0xB9,0xD5,0xEA,0xB3,0xC9,0x6C,0xF1,0xD5,0xE9,0x4A,0xB6,0xBD,0x39,0x7F,0x21,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x20,0x80,0x48,0xD3,0x08,0x90,0x54,0x28,0x06,0xFE,0x1F};
const uint8_t spIS[] PROGMEM = {0xAD,0xED,0xD5,0x58,0xA4,0x9E,0xCE,0x76,0xF5,0xDD,0xAB,0x29,0xF5,0xD2,0xDD,0xEF,0x7E,0x0C,0xC3,0xA9,0x06,0xFA,0xD3,0x32,0x0F,0x6E,0x94,0x22,0x8F,0xF3,0x92,0xF6,0x05,0x43,0xCC,0x74,0x77,0x3E,0xC3,0xF5,0x95,0x98,0xA9,0xBA,0x8B,0x8F,0x00,0x7E,0x73,0xE5,0x00,0x05,0x28,0xF0,0xFF};
const uint8_t spALERT[] PROGMEM = {0xA5,0xCF,0xC6,0xAB,0x55,0x5B,0xAF,0x39,0xDA,0xC9,0x54,0xDD,0xBC,0xC6,0xC2,0x3C,0x27,0x20,0xCF,0x1C,0xD7,0x30,0xB0,0x45,0x16,0x69,0x1D,0xC3,0x11,0xE4,0x59,0x8A,0x7C,0xB5,0x9B,0x8B,0xD9,0x30,0xB7,0xD3,0x76,0x19,0x9A,0x25,0x59,0x57,0x59,0xEC,0x11,0xAF,0xE8,0xD9,0xF9,0x2A,0x8A,0x1D,0xF0,0x75,0x3F,0x73,0xAC,0x87,0x3B,0xA2,0x0B,0xAA,0x2B,0xCF,0xE4,0x10,0xA1,0xDC,0x45,0x64,0x03,0x00,0x80,0x01,0x66,0x36,0x33,0xC0,0xAB,0xD5,0x0A,0x68,0x25,0x85,0x02,0xFF,0x0F};
const uint8_t spADJUST[] PROGMEM = {0xAD,0xAD,0xA1,0xD5,0xC4,0x5A,0x9F,0xB1,0xFA,0x14,0xB3,0x78,0xBC,0x87,0x31,0x55,0x9B,0xEC,0xC2,0x6B,0xC4,0xE6,0xB9,0xDB,0xB8,0x97,0x24,0x87,0xA6,0x99,0x59,0x61,0x4B,0x1C,0x05,0x63,0x56,0x79,0x6C,0x05,0x4C,0xC5,0x14,0x81,0x35,0xB4,0x98,0xAC,0xAE,0x7D,0x6E,0x77,0xAA,0xE2,0xD2,0x5A,0x63,0xD5,0xAD,0x6E,0xBD,0xBA,0xE2,0xD3,0x8A,0xAB,0xF2,0x1C,0x15,0x50,0x41,0x8A,0x03,0x7E,0x29,0xF1,0x80,0x05,0x2C,0xA0,0x01,0x01,0xFC,0xD6,0x2A,0x01,0x60,0xC0,0x0B,0xEC,0x16,0x60,0x40,0xB7,0x63,0xFF,0x0F};
const uint8_t spBETWEEN[] PROGMEM = {0xA2,0xED,0xD9,0x59,0x4C,0xFB,0xEC,0xE2,0x0C,0x33,0x34,0x83,0xD9,0x96,0x3B,0x8E,0x69,0xC6,0x15,0x14,0xDA,0x03,0xE0,0x80,0x6E,0xCD,0x03,0xD0,0xE3,0xB8,0x02,0x72,0x48,0x2B,0x45,0xB0,0xE9,0x69,0x12,0x77,0x55,0x99,0xA7,0x57,0x42,0x93,0x53,0x74,0x19,0xE6,0x89,0x6B,0x4E,0x39,0x82,0xB3,0xA6,0x3E,0x3A,0xE5,0x2C,0x81,0x5C,0x59,0xE9,0xD6,0xAB,0xEB,0x81,0x31,0x27,0xCA,0xCC,0xA5,0x6F,0x65,0x1B,0x09,0x5D,0x3D,0xDC,0xD4,0x23,0x9F,0xE9,0xA9,0x8A,0xB4,0xDD,0x92,0xFC,0x3F};
const uint8_t spMINUTES[] PROGMEM = {0x61,0xCA,0xCC,0x38,0x5B,0x9A,0xE6,0xA9,0xB6,0xA7,0xEC,0x2A,0xC5,0xDD,0x17,0xDF,0xE2,0xE6,0x23,0x6B,0x16,0xC3,0x2D,0x92,0xCC,0x72,0xB5,0xD5,0xBA,0x86,0xD5,0xEC,0xB9,0x94,0xAD,0x98,0x90,0xF4,0x79,0x14,0xDE,0x8E,0x53,0x3C,0x63,0x23,0x02,0x45,0x28,0x77,0x11,0xD9,0x00,0x80,0x80,0xCF,0x58,0x05,0xF0,0x7B,0x99,0x04,0x38,0xC0,0x01,0x0A,0x50,0xE0,0xFF,0x01};
const uint8_t spBUTTON[] PROGMEM = {0x10,0xA6,0x28,0xDD,0xCD,0x2D,0xD5,0x6A,0x8B,0xEE,0x6C,0xB1,0x4D,0xA7,0xAC,0x2E,0xA3,0x44,0x97,0xDC,0xA6,0xF5,0xCD,0x6B,0x34,0x46,0x13,0x32,0x89,0x50,0xEE,0x22,0xB2,0x01,0x20,0xA5,0xDD,0xA1,0x94,0xBB,0xB3,0xB6,0x0C,0x2F,0xA4,0xE6,0xF1,0xFA,0x96,0x8F,0x70,0x8F,0xC2,0x2A,0xE6,0x4A,0xDD,0xD3,0x2D,0x51,0x7A,0xDA,0xF3,0xAF,0x7B,0x47,0x63,0x51,0x73,0x67,0xE1,0x6B,0x46,0xDD,0x49,0xEB,0xFE,0x3F};
const uint8_t spCLOCK[] PROGMEM = {0x06,0x48,0x65,0x34,0x00,0x93,0xA7,0x5B,0xA0,0xA4,0x95,0xBA,0x5F,0x82,0x9B,0x95,0x07,0x37,0x55,0x24,0x4D,0x4E,0x51,0xE9,0x54,0x25,0x76,0xB9,0xE5,0x2D,0x4F,0x93,0x7D,0xE5,0x98,0xAE,0xDE,0x63,0x3B,0x72,0xC9,0x2C,0x8E,0xD9,0xF1,0x41,0xA0,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x40,0x00,0x35,0x0D,0x69,0x80,0x02,0xFF,0x0F};
const uint8_t spDEVICE[] PROGMEM = {0x64,0x8E,0x38,0x3C,0x4B,0x62,0x8F,0x7D,0x89,0x14,0xD4,0xCC,0xB5,0x86,0x11,0x9A,0xD1,0xB5,0xCF,0x1C,0xDC,0xDC,0xA5,0x23,0xB5,0x3B,0xCB,0x73,0x9D,0x46,0x99,0x6D,0x59,0x35,0xE5,0xD9,0xF5,0x69,0xAA,0x1E,0xCB,0xE2,0xCD,0xB7,0xB9,0xDD,0x19,0xAA,0x2F,0xE9,0xD0,0xD5,0x7B,0x69,0x57,0xF3,0x49,0x1E,0xF1,0x28,0xDE,0x0C,0xB8,0x36,0x54,0x00,0xBF,0x55,0x6A,0x40,0x03,0x1A,0xE0,0x00,0x07,0x28,0xF0,0xFF};
const uint8_t spEAST[] PROGMEM = {0xAD,0x1D,0x59,0x50,0xBC,0x17,0x8F,0x7A,0x96,0x02,0x8C,0x7C,0xB2,0xEB,0x5D,0xCD,0x7A,0x0C,0x63,0x10,0x71,0xCC,0xEC,0x3E,0xA5,0x75,0x0C,0x41,0xF2,0x7A,0x4C,0x80,0x6F,0x67,0x24,0xA0,0x01,0x05,0xFC,0x3C,0xA5,0x01,0x0D,0x58,0x40,0x02,0x04,0xF8,0xDA,0x1C,0x03,0x1A,0x30,0xC0,0x31,0x37,0x02,0xE8,0xF5,0x8D,0x00,0xD5,0x39,0xFC,0x3F};
const uint8_t spFAIL[] PROGMEM = {0x04,0x98,0x3E,0x8D,0x03,0x1C,0xD0,0x80,0x07,0x4A,0xBF,0x54,0x9B,0x3A,0x79,0x9C,0xCD,0xAA,0x9B,0x0F,0x31,0x8F,0x37,0xB7,0xBE,0xCD,0x6A,0x47,0x2A,0x66,0xB3,0xB7,0xB3,0xDB,0x6B,0x5F,0xC7,0x56,0x44,0x58,0x8E,0x76,0xAA,0x7B,0xD8,0x33,0xB9,0x32,0xD7,0x3C,0xF9,0x0C,0x67,0xD4,0x13,0x9E,0x98,0xC7,0x5F,0xEE,0x49,0x7C,0xAA,0x8D,0xF3,0xF9,0xF7,0xFF,0x01};
const uint8_t spFREQUENCY[] PROGMEM = {0x04,0xA8,0x4A,0x9D,0x01,0x33,0x8C,0x71,0x40,0x02,0x1A,0x08,0x71,0x4E,0x5C,0x52,0xEA,0x7E,0x67,0x2B,0xEB,0xB5,0x98,0x82,0xB7,0xEE,0x64,0xA4,0x7D,0x18,0xB2,0xDB,0x1B,0x9B,0x22,0x50,0x84,0x72,0x17,0x91,0x0D,0x04,0xF0,0x35,0x2D,0x25,0x59,0xB9,0x57,0xCA,0xE2,0x39,0xB4,0xB1,0x69,0xB4,0xF2,0xB4,0x5B,0x97,0xB0,0x14,0x05,0x15,0x91,0x6A,0xF4,0x2A,0x80,0x5F,0x4A,0x2D,0xE0,0x01,0x0B,0x68,0x40,0x03,0x63,0x69,0x56,0xC5,0x25,0x57,0x8D,0xAD,0x27,0x63,0xB1,0x78,0xDC,0x8F,0x7E,0x95,0x6B,0xE6,0x24,0x32,0x5B,0x93,0xEE,0xD1,0x83,0x58,0xEC,0x4D,0x7E,0xE3,0xF7,0xFF};
const uint8_t spGATE[] PROGMEM = {0x0C,0x08,0xDA,0x75,0x2C,0xB3,0x27,0x19,0xBB,0xDD,0xD1,0xB7,0x44,0xE4,0x51,0x73,0x4E,0x3D,0x7A,0x90,0x49,0x2C,0xB9,0xE5,0xAD,0x6E,0xB5,0xBA,0x99,0x0A,0x24,0xE3,0xF1,0x1E,0xFA,0x1E,0xEE,0x31,0x13,0x59,0xE3,0x8D,0xFA,0x47,0x21,0x32,0xAF,0xC7,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x00,0x38,0x60,0x89,0x52,0x03,0x6C,0xF3,0xC3,0x80,0xDE,0xD7,0x08,0x50,0x8D,0xE1,0xFF,0x03};
const uint8_t spHIGH[] PROGMEM = {0x04,0xC8,0x7E,0x9C,0x02,0x12,0xD0,0x80,0x06,0x56,0x96,0x7D,0x67,0x4B,0x2C,0xB9,0xC5,0x6D,0x6E,0x7D,0xEB,0xDB,0xDC,0xEE,0x8C,0x4D,0x8F,0x65,0xF1,0xE6,0xBD,0xEE,0x6D,0xEC,0xCD,0x97,0x74,0xE8,0xEA,0x79,0xCE,0xAB,0x5C,0x23,0x06,0x69,0xC4,0xA3,0x7C,0xC7,0xC7,0xBF,0xFF,0x0F};
const uint8_t spINTRUDER[] PROGMEM = {0xAB,0x1D,0xA9,0x88,0xCC,0x37,0x9F,0x66,0xBA,0x16,0x31,0xFE,0xBC,0xEB,0x55,0x0F,0xCF,0x98,0x69,0x55,0x47,0xD3,0x0C,0xF2,0xA4,0x45,0xAB,0x6D,0x6D,0x43,0x57,0x34,0xF8,0x78,0x34,0x45,0xA0,0x08,0xE5,0x2E,0x22,0x1B,0x14,0xD0,0x4A,0x46,0x06,0x34,0xD0,0xD2,0xEC,0x39,0xCC,0xCC,0xDD,0xCC,0x56,0x9E,0x95,0x58,0x14,0xB5,0xDB,0x45,0xAB,0xAB,0x27,0x4B,0xF6,0x74,0xA2,0x62,0xCE,0xB2,0x3C,0x66,0xB7,0x7A,0x2C,0x0B,0x61,0x95,0xBB,0x96,0x96,0x4C,0xD9,0x35,0xDB,0x98,0xAB,0x29,0xA2,0xB3,0x7C,0x73,0xED,0x47,0xBB,0x4A,0x2E,0xD0,0x71,0x3F,0xF9,0x8B,0x5F,0xF8,0x4A,0x0F,0xF4,0xD1,0x3C,0xFF,0x0F};
const uint8_t spMEASURE[] PROGMEM = {0x66,0x71,0x52,0xED,0xD2,0x92,0x86,0x39,0x2B,0xE6,0x4E,0x8F,0x9B,0xC7,0xD1,0x17,0xA3,0x1C,0x22,0x69,0x4F,0xD7,0x73,0xA8,0x9B,0xAE,0xBE,0xF5,0xAD,0x6E,0x39,0xF2,0xEE,0x45,0xD4,0x7C,0xA5,0x01,0x1A,0x63,0x0E,0xC0,0xA8,0x81,0x11,0x18,0x7D,0x8F,0x29,0x68,0x96,0x75,0x0C,0x25,0x27,0x71,0x85,0xF7,0x39,0xCF,0x7D,0x1E,0xE5,0x2A,0x4B,0xD8,0x5B,0xF3,0xE4,0x27,0x3E,0xFE,0x75,0x7F,0x19,0x46,0xD9,0xBC,0xE5,0xFF,0x01};
const uint8_t spNORTH[] PROGMEM = {0x66,0x8E,0x54,0xAC,0x9A,0xE7,0x84,0xA9,0x0A,0xE2,0x1C,0xAE,0x5B,0xC6,0xE6,0x51,0xCD,0x23,0xE9,0xE9,0x8B,0x71,0x77,0xD3,0xAE,0xA7,0x2A,0x22,0x3D,0x8B,0xB2,0x9E,0x32,0x8B,0xCE,0x6C,0xD6,0x76,0x8B,0x55,0x26,0xB7,0xE2,0xCB,0x7A,0x77,0x35,0x87,0xB6,0xE5,0x92,0x54,0xA9,0xF9,0xC6,0x91,0x63,0x88,0xA7,0x77,0xEE,0x67,0xBA,0x4B,0x60,0x2F,0xAB,0xD6,0x04,0x18,0xB2,0x44,0x03,0x06,0xC8,0xB2,0x44,0x03,0x14,0xA0,0xC0,0xFF,0x03};
const uint8_t spPASS[] PROGMEM = {0x0A,0xC8,0x33,0x83,0x03,0xA3,0xEC,0x55,0x2D,0xD4,0x12,0xAF,0xAA,0x04,0xC9,0xD4,0x0E,0x7D,0xAA,0x16,0x4A,0x33,0x65,0xCE,0xAD,0x6F,0x7D,0x9A,0x9A,0xDC,0xDB,0x62,0xEE,0x6D,0x6E,0x73,0xC6,0x12,0xDD,0x5B,0x6B,0xEE,0x5D,0xF6,0x3A,0xCE,0xAA,0xD2,0x26,0xED,0x75,0xBB,0x9B,0x4D,0x6D,0xF1,0x25,0xFD,0x77,0x7F,0xEF,0xD2,0xCE,0x9D,0x46,0x00,0x4B,0x17,0x2B,0xE0,0x8F,0x52,0x0B,0x68,0x40,0x02,0x1C,0x90,0xC0,0xFF,0x03};
const uint8_t spPOSITION[] PROGMEM = {0x02,0xC8,0x3C,0x78,0x24,0x5D,0xB8,0xBB,0x53,0xB7,0x5B,0xDC,0x62,0xD5,0x4B,0x38,0x87,0xA1,0x1F,0x05,0x5C,0x40,0x66,0x81,0x95,0x1D,0x19,0xA6,0x4E,0x7E,0x4E,0x3C,0x75,0xA8,0x39,0xF5,0x3D,0x51,0xB7,0xA9,0xA6,0xBA,0xE7,0x44,0x2D,0x99,0x2A,0xC7,0xA6,0x04,0x8C,0x3E,0x95,0x81,0x0C,0x78,0xA0,0xF5,0x2D,0xA8,0x98,0xD9,0x96,0x3D,0x8D,0x69,0xE8,0x64,0x4B,0xE9,0x3B,0x8E,0xA1,0x9D,0xBD,0xA4,0x4B,0x3B,0xBA,0x16,0x2C,0x77,0x7B,0xF9,0xCA,0x4F,0x78,0x7B,0x20,0x35,0x0B,0xA7,0xF1,0xFF,0x7F};const uint8_t spPUSH[] PROGMEM = {0x06,0x28,0x22,0x5D,0x03,0xCB,0x4B,0x2A,0x23,0x03,0xDB,0x9E,0xB8,0x88,0x8C,0x18,0xCC,0x7A,0xD3,0x9B,0xAF,0xBA,0x78,0xE7,0x70,0xEB,0xDA,0xC6,0x9E,0x27,0x44,0x44,0xAB,0x01,0x56,0xBE,0x8A,0x40,0x04,0x22,0xE0,0x01,0x0F,0x78,0x40,0x02,0xFF,0x0F};
const uint8_t spRIGHT[] PROGMEM = {0x66,0xD7,0xB1,0x24,0xDC,0xE3,0x98,0xCD,0x95,0xA4,0x28,0xB5,0x97,0xD6,0xD0,0x8C,0x3A,0x55,0xFE,0x18,0x43,0xB1,0x4C,0x37,0x6F,0xA7,0x2D,0x72,0x22,0x8A,0xF3,0x9E,0xA6,0xFA,0x94,0x0A,0xDD,0x7C,0x9B,0xDB,0xAD,0xB1,0xD7,0x40,0xF3,0x78,0x3D,0xE7,0x7E,0xE6,0x07,0x81,0x22,0x94,0xBB,0x88,0x6C,0x00,0x50,0xC0,0xB6,0xD7,0x1E,0x10,0x40,0x9B,0xEB,0x0C,0x28,0x56,0xE9,0xFF,0x01};
const uint8_t spSLOW[] PROGMEM = {0x04,0xF8,0xCB,0x44,0x01,0xBF,0x86,0x5B,0xC0,0x02,0x1C,0x28,0xD3,0xC6,0x1C,0x55,0xA2,0xAD,0x0F,0xB3,0x3D,0xC5,0xA4,0x16,0x95,0xE4,0xF5,0x64,0x95,0x7B,0x8E,0x53,0xDF,0x9B,0xAD,0x22,0xF1,0xEA,0x61,0xCE,0xBB,0x9B,0xD9,0xCF,0xB9,0x2F,0x7D,0x0D,0x9B,0xD7,0x5D,0x0B,0x92,0x27,0x1E,0xEE,0xD4,0xA5,0x32,0x50,0xDB,0xD8,0xD3,0x5E,0xEE,0xF6,0xB1,0xDD,0x55,0xBB,0xFC,0x3F};
const uint8_t spTOOL[] PROGMEM = {0x09,0x38,0xD6,0xCC,0x01,0xCB,0x76,0xB5,0x38,0x73,0x0B,0x4F,0xCA,0x3A,0x92,0x42,0xAD,0x25,0x29,0xFD,0x4E,0x47,0x9A,0x78,0x64,0x34,0xA4,0xEB,0xC5,0xA8,0x0A,0xB1,0xCA,0x02,0x77,0xB5,0xAF,0x73,0x5A,0x83,0x88,0x69,0xA3,0x6C,0x69,0xCD,0xCC,0x67,0x94,0xDC,0xE7,0x3D,0x5E,0xF1,0x09,0x7F,0x11,0xDA,0xC3,0xE2,0xF5,0xFF,0x01};
const uint8_t spWEST[] PROGMEM = {0x66,0xB7,0x7C,0x53,0x53,0x6B,0xFA,0xC5,0xCF,0x65,0x4C,0x64,0x56,0x5C,0x1C,0xAF,0xA6,0xE0,0xEA,0x68,0x52,0x77,0x8A,0x2A,0xD2,0xB3,0x29,0xDF,0xC9,0x9B,0x4A,0xCD,0xE2,0xCD,0x37,0x5F,0x45,0x8B,0x21,0xAD,0xF1,0x78,0xB7,0xBB,0x1F,0x4B,0x89,0x92,0xC6,0x17,0x5B,0x01,0x8F,0x9B,0x1A,0xE0,0x97,0x48,0x0F,0x78,0xC0,0x03,0x1A,0x10,0xC0,0x9F,0xED,0x1C,0xC0,0x00,0x28,0xE0,0x15,0x56,0x05,0x1C,0x9F,0x43,0x80,0x61,0x26,0xFF,0x1F};
const uint8_t spKILO[] PROGMEM = {0x06,0xD8,0x29,0x25,0x01,0x5D,0x22,0x7B,0xA0,0x85,0x33,0x1A,0x52,0xD7,0xDB,0x19,0xCF,0x68,0x44,0xD3,0x29,0x51,0x79,0xBC,0x99,0xAC,0x6C,0x71,0x0B,0x4D,0xCA,0xB6,0xC7,0x35,0x55,0xEE,0x39,0x4E,0x7D,0xEF,0xBA,0xD6,0xC2,0x32,0xAB,0xB8,0xEF,0xDE,0xDB,0x99,0x4C,0x65,0x2B,0xF5,0xED,0x67,0xB9,0x7D,0xAC,0x6C,0xD4,0x35,0xF1,0x8E,0x4F,0x78,0x83,0x9A,0xCA,0x20,0xBF,0xEE,0x4F,0x62,0xBC,0x82,0xF4,0xFD,0x3F};
const uint8_t spAND[] PROGMEM = {0xA9,0x6B,0x21,0xB9,0x22,0x66,0x9F,0xAE,0xC7,0xE1,0x70,0x7B,0x72,0xBB,0x5B,0xDF,0xEA,0x56,0xBB,0x5C,0x65,0xCB,0x66,0xC5,0x3D,0x67,0xD7,0xAB,0x6D,0x2E,0x64,0x30,0x93,0xEE,0xB1,0xCD,0x3D,0x92,0xB9,0x9A,0xDA,0xB2,0x8E,0x40,0x12,0x9A,0x6A,0xEB,0x96,0x8F,0x78,0x98,0xB3,0x2A,0xB4,0xD3,0x48,0xAA,0x2F,0x7D,0xA7,0x7B,0xFB,0x0C,0x73,0x71,0x5C,0xCE,0x6E,0x5C,0x52,0x6C,0x73,0x79,0x9A,0x13,0x4B,0x89,0x45,0xE9,0x6E,0x49,0x42,0xA9,0x57,0xFF,0x3F};
const uint8_t spFARAD[] PROGMEM = {0x04,0x58,0x3E,0x8D,0x03,0x1C,0xD0,0x80,0x05,0x4A,0xB9,0x54,0x9B,0x3A,0x79,0x9C,0xD5,0xA9,0x7B,0x0C,0x71,0xF7,0xD7,0xB7,0xBE,0xCD,0x68,0x4B,0x56,0xF1,0x12,0x3F,0xB5,0x4B,0x6B,0x2C,0x6C,0x91,0x26,0xBF,0x4E,0x63,0x2E,0x91,0x43,0x5D,0xDB,0xAF,0xA5,0xF9,0x10,0x0D,0xE9,0x3E,0xF7,0x7A,0xF2,0x0B,0x81,0x22,0x94,0xBB,0x88,0x6C,0x20,0xCF,0xA2,0xEE,0x95,0x99,0x38,0x3D,0xDD,0x85,0x89,0xCA,0x96,0xFC,0xFC,0x3F};
const uint8_t spMILLI[] PROGMEM = {0x6E,0xF0,0x8A,0xB3,0x4B,0xEB,0xC6,0xAE,0x36,0xA7,0x1A,0x3A,0x54,0x53,0xD6,0xDC,0xEC,0x66,0x23,0xDF,0x58,0x26,0x43,0xB4,0xCD,0xEA,0x74,0x5D,0x94,0x46,0xF0,0x96,0x3B,0x9D,0x79,0x98,0x26,0x75,0xDB,0xB3,0xD7,0xB6,0xF5,0x90,0xA8,0x91,0x9F,0xEA,0x9E,0xEE,0xE9,0x9B,0x20,0x7D,0xCB,0xFF,0x03};
const uint8_t spCAUTION[] PROGMEM = {0x02,0x48,0x69,0x4D,0x03,0x06,0xE8,0x34,0xA2,0x85,0x95,0x4C,0x78,0xA8,0xD2,0x93,0x66,0xB1,0xE9,0x4D,0x79,0x6F,0x7A,0xD3,0x9D,0xF5,0xCC,0x01,0x2B,0x86,0x06,0x60,0xC5,0xAB,0x08,0x44,0x20,0x00,0xCD,0x10,0x8D,0xB6,0x26,0x11,0x8B,0xE8,0x3C,0xE6,0x62,0x5D,0x3D,0x63,0xF7,0x58,0xBB,0x4E,0xF1,0xB0,0x2E,0xED,0x28,0xCA,0x74,0xCC,0x9B,0xB8,0xB7,0x69,0xA6,0x0E,0x8F,0x66,0xBE,0xAC,0x48,0xC6,0xAD,0xAE,0xFB,0x9A,0x16,0x0E,0xF3,0x78,0xFE,0xF3,0xBF,0xFF,0xED,0xFF,0xFF};
const uint8_t spLIGHT[] PROGMEM = {0x61,0x69,0xC0,0x2B,0x82,0xB3,0xA5,0x79,0x01,0x9A,0x52,0x71,0x57,0xC7,0x31,0x0C,0x5C,0x5D,0xC1,0x59,0x6F,0x7B,0x9A,0xC6,0x3B,0xCB,0xA5,0xCB,0xA9,0xAA,0x6D,0x6B,0xB3,0xCD,0xA7,0x6C,0x29,0xB4,0x34,0x56,0xAF,0xBA,0x0F,0x23,0x93,0x5C,0x32,0xC7,0xB6,0xF6,0x46,0xA4,0x39,0xB3,0xF3,0x86,0x40,0x11,0xCA,0x5D,0x44,0x36,0x00,0x80,0x02,0x96,0x2A,0x35,0xC0,0xB6,0x97,0x0C,0xE8,0xF9,0x04,0x01,0xC5,0x19,0xFC,0x3F};
const uint8_t spCHECK[] PROGMEM = {0x0E,0x58,0x25,0x25,0x00,0xB3,0x8E,0x7B,0x60,0xC5,0x35,0xB3,0x68,0xE4,0xEA,0x53,0xB4,0x1C,0x12,0xEE,0x9B,0x6F,0x79,0xAB,0x5B,0xEF,0x71,0xEF,0xE6,0xAE,0x49,0xA9,0x2A,0x17,0x21,0x50,0x84,0x72,0x17,0x91,0x0D,0x00,0x0A,0x68,0xC5,0x49,0x02,0x12,0xE0,0xC0,0xFF,0x03};
const uint8_t spDEGREES[] PROGMEM = {0x65,0x9F,0x5A,0x48,0x42,0x1D,0x8F,0x61,0xB8,0x62,0x56,0xFE,0xB2,0xFA,0x51,0x9C,0x85,0xED,0xCD,0xEA,0x47,0x4B,0x64,0xD5,0x35,0x69,0xE8,0xC7,0x41,0xD4,0x5E,0x8B,0x25,0x6B,0xB4,0x75,0xB7,0x84,0x40,0x11,0xCA,0x5D,0x44,0x36,0x98,0xAD,0xA9,0xAB,0x28,0x8D,0x1B,0xFA,0xE2,0x26,0xC9,0x44,0x69,0x6A,0xA3,0x13,0x8F,0x70,0xAD,0xA5,0xC9,0x99,0x42,0xDC,0x9C,0x8D,0xA6,0x36,0x4E,0x72,0xB3,0xBF,0xEA,0xD6,0x54,0xD9,0x25,0xFD,0xAA,0x46,0x19,0x86,0x90,0xAF,0xB3,0xEE,0x4D,0x19,0x47,0x12,0x90,0xCE,0x5B,0x75,0xC9,0x5B,0xDA,0x47,0x31,0x14,0xF3,0xD7,0xF9,0xCC,0x77,0xFC,0xFC,0xEF,0xFE,0xE6,0x99,0xC2,0x7C,0x93,0xFE,0xC5,0xDF,0x44,0x08,0x5B,0x75,0x36,0xFF,0xD2,0xC6,0xE2,0x91,0xCE,0xFD,0xDF,0x89,0x9A,0x68,0x3A,0x01,0x4C,0x48,0x2A,0x80,0x5F,0x33,0x34,0x40,0x81,0xFF,0x07};
const uint8_t spSERVICE[] PROGMEM = {0x04,0xF8,0xAD,0x94,0x03,0x1A,0xB0,0x80,0x07,0x2C,0xB0,0xA2,0xE6,0xCD,0xD4,0xB4,0xEB,0xC9,0xAA,0x4D,0xE1,0xD6,0xEC,0x23,0x2B,0xBE,0x85,0x96,0xFD,0xCD,0xBC,0x15,0xB9,0x16,0xE9,0xB0,0xBF,0x51,0x66,0x5F,0x24,0xA3,0x7A,0x53,0x97,0xBD,0x89,0xBB,0xC4,0x52,0x4B,0xB1,0xAE,0xE6,0x9A,0xB9,0xEE,0x63,0xAD,0xCE,0x35,0xD4,0x7A,0xCF,0xA3,0x9F,0xE9,0x2E,0xD2,0x25,0xDD,0x77,0x13,0xE0,0xB7,0x52,0x09,0x48,0xC0,0x02,0x16,0x90,0x00,0x05,0xFE,0x1F};
const uint8_t spSWITCH[] PROGMEM = {0x08,0xF8,0x3B,0x93,0x03,0x1A,0xB0,0x80,0x01,0xAE,0xCF,0x54,0x40,0x33,0x99,0x2E,0xF6,0xB2,0x4B,0x9D,0x52,0xA7,0x36,0xF0,0x2E,0x2F,0x70,0xDB,0xCB,0x93,0x75,0xEE,0xA6,0x4B,0x79,0x4F,0x36,0x4C,0x89,0x34,0x77,0xB9,0xF9,0xAA,0x5B,0x08,0x76,0xF5,0xCD,0x73,0xE4,0x13,0x99,0x45,0x28,0x77,0x11,0xD9,0x40,0x80,0x55,0xCB,0x25,0xE0,0x80,0x59,0x2F,0x23,0xE0,0x01,0x0B,0x08,0xA0,0x46,0xB1,0xFF,0x07};
const uint8_t spVALVE[] PROGMEM = {0x61,0x1F,0x5A,0x58,0x4D,0x9C,0x08,0x60,0x58,0x95,0x32,0x0D,0x2D,0xAC,0x26,0x4E,0x46,0xD7,0x5C,0x58,0x18,0xAF,0x3E,0x6D,0x73,0x6A,0x65,0xF6,0xE4,0x34,0xCD,0xA6,0x97,0xD9,0x93,0x5B,0xDF,0xFA,0x36,0xAB,0xCF,0x6A,0xA3,0x55,0x36,0xEF,0x7E,0xCF,0x63,0x2E,0xF4,0xAA,0x9C,0xFA,0x8C,0xAD,0xC1,0x9E,0x76,0xF2,0xD6,0xF7,0xBA,0xD7,0xA3,0x1C,0x85,0x78,0x76,0xA1,0xFA,0x78,0xC4,0x3B,0xDC,0x91,0x55,0x94,0x70,0x6A,0x7F,0xEB,0x87,0x00,0x55,0xA8,0x70,0x80,0x02,0x14,0xC0,0xC0,0xFF,0x03};
const uint8_t spVAL[] PROGMEM = {0x24,0x4B,0x38,0x2C,0x43,0x13,0xBB,0xEC,0xB8,0xB6,0xD0,0x76,0xBD,0xDA,0x6D,0x4B,0xC5,0xD8,0xF7,0x69,0x9B,0x55,0x2B,0xB3,0x27,0xA7,0x69,0x36,0xAD,0xCC,0x9E,0xDC,0xFA,0xD6,0xB7,0x59,0x7D,0x56,0x1B,0xAD,0xB2,0x79,0xF7,0x73,0x68,0x73,0x0C,0x5D,0xE1,0xD2,0xA6,0xEE,0xF9,0x0C,0x57,0xB0,0x13,0xC1,0x9E,0x36,0x5E,0xEE,0xCE,0x22,0xAC,0xD5,0xE2,0xF8,0xDB,0xDC,0x4D,0x09,0xA5,0x47,0xDC,0x78,0x9B,0xBB,0x7B,0x62,0xB7,0x70,0xF6,0xFF};
const uint8_t spNUMBER[] PROGMEM = {0x66,0xA9,0x12,0x72,0x42,0x9B,0x86,0xA5,0x1B,0x90,0x0E,0x6D,0x76,0xA6,0x26,0x2B,0xDC,0xA5,0xCF,0x6D,0x4F,0x95,0x4D,0xA5,0xBB,0x6E,0x5E,0x45,0x31,0x5E,0x65,0x92,0x66,0x14,0x45,0xAA,0xB4,0x98,0x9D,0x5A,0x84,0x2A,0x18,0xF6,0x92,0x74,0x43,0x3A,0xAD,0x5C,0x27,0xDD,0x6D,0x98,0xA3,0x09,0xF5,0x92,0xA4,0x65,0x4C,0x4D,0xA4,0x82,0x56,0x97,0x39,0x77,0xC7,0x68,0xF1,0x5D,0xD6,0xDC,0x1D,0x63,0xD4,0x4F,0xBE,0xC3,0x9D,0x53,0x81,0x4E,0xF3,0x89,0x9F,0xFF,0xDC,0x5F,0x66,0x92,0xB5,0x7A,0xFE,0x7F};
const uint8_t spOUT[] PROGMEM = {0xAD,0xCF,0xE6,0xDD,0xD3,0x17,0xED,0xFE,0xF4,0x9D,0x4F,0x56,0x71,0x97,0xDB,0xDD,0xEE,0x76,0xA7,0xCF,0xAE,0x6A,0x54,0x5A,0xEF,0x7E,0x0F,0x7B,0x4C,0x6B,0x88,0x95,0x21,0xBC,0xD9,0x6F,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x00,0x08,0xE0,0xE8,0x2E,0x0F,0x50,0xE0,0xFF,0x01};
const uint8_t spPOINT[] PROGMEM = {0x06,0xA8,0xCC,0x4B,0x03,0x2D,0xF3,0x69,0x2B,0x8C,0x1A,0xAF,0x2C,0x98,0xE9,0x28,0x4A,0xB3,0xF3,0x53,0xC6,0x90,0x9E,0xC1,0x6D,0x76,0x77,0xE6,0x9C,0x5D,0xD3,0x75,0xF1,0x58,0x5B,0x75,0x76,0xB7,0x4F,0xE3,0xE8,0xCE,0x31,0x3A,0x17,0xB6,0xB3,0x45,0x96,0xF4,0xAA,0x6D,0x4F,0x75,0x76,0xA3,0x94,0x66,0x6E,0x10,0x28,0x42,0xB9,0x8B,0xC8,0x06,0x50,0xC0,0x32,0x11,0x0A,0x58,0x76,0x87,0x01,0x3D,0xB5,0xFE,0x3F};
const uint8_t spBREAK[] PROGMEM = {0x90,0xC6,0x62,0x2D,0xDC,0xCC,0x76,0xE9,0x63,0x55,0xD3,0x32,0xF5,0xAD,0x4F,0x5D,0x42,0x53,0xF5,0x9D,0xB6,0x14,0x49,0x0D,0xCD,0x73,0xEA,0x5A,0x4C,0xC3,0x6D,0xF3,0x69,0x7A,0x0B,0x52,0x8D,0x25,0xBB,0x9D,0x8B,0xDB,0xC7,0x13,0x90,0x8A,0xC7,0x08,0x14,0xA1,0xDC,0x45,0x64,0x03,0x00,0x03,0xC6,0xA8,0x14,0x40,0xCD,0x4A,0x16,0xE0,0x00,0x06,0xFE,0x1F};
const uint8_t spHOURS[] PROGMEM = {0x63,0xC9,0x66,0xA2,0xCC,0x57,0x9F,0xB1,0xF1,0xCE,0x6E,0xEE,0x72,0xBB,0xD3,0x24,0x3B,0x99,0x49,0x79,0x6E,0x35,0x2A,0x1F,0x27,0xBD,0xC8,0x4B,0x69,0x4D,0xDA,0xB0,0x54,0x2E,0x65,0xB0,0x65,0x34,0x43,0xF8,0x96,0x31,0x75,0xA5,0x6E,0xEA,0x53,0xD7,0x7C,0xA4,0x27,0xD7,0x00,0x6F,0xD7,0x1B,0x1F,0xFF,0xB8,0xB7,0x26,0x16,0x49,0xEB,0xE6,0x5F,0xF7,0x56,0x2B,0x62,0xEA,0xEB,0xDC,0xDB,0x83,0xB2,0x9A,0x74,0x73,0xEF,0x76,0x9E,0xC4,0xAA,0xDE,0x7D,0xBF,0x87,0xA6,0xA0,0x52,0x06,0x7C,0x4B,0x24,0x01,0x09,0x70,0xE0,0xFF,0x01};
const uint8_t spCALIBRATE[] PROGMEM = {0x0E,0x18,0xC9,0xD9,0x01,0x55,0x29,0x9E,0xA0,0x16,0x97,0x70,0x5F,0x7C,0xB2,0xAA,0xDB,0x2B,0x79,0xCD,0xCD,0x56,0x51,0xC9,0x54,0x0D,0x26,0x1E,0x45,0xC3,0x55,0xDE,0xE2,0xF8,0x54,0xC5,0x94,0xA7,0x73,0x97,0xDB,0x94,0x3E,0xE9,0x52,0x2F,0xF6,0xC2,0x16,0xA9,0x4B,0xB3,0xCC,0x5E,0xD8,0xAA,0x34,0x31,0x73,0x27,0xE5,0x4C,0x8D,0xC3,0xD3,0xF4,0xF6,0xA9,0x2F,0xEB,0xA8,0x2E,0x39,0x42,0xFB,0x8E,0xAB,0x99,0xA4,0x28,0xFF,0x5C,0xEE,0x69,0x97,0x28,0x7D,0x4F,0x7D,0xD2,0xDF,0xAB,0x92,0x98,0x6F,0x41,0x8F,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x18,0xB0,0x42,0xA4,0x02,0x5E,0xA8,0x26,0xC0,0xF0,0xE7,0xFF,0x0F};
const uint8_t spCRANE[] PROGMEM = {0x0A,0xC8,0xBD,0xD5,0x03,0x16,0x50,0x40,0x5E,0x15,0x23,0x4F,0x5D,0xCC,0x87,0xB3,0xAE,0xA2,0xE4,0x64,0x1D,0x73,0x7F,0x8A,0x9A,0x9B,0xB5,0xA5,0xEB,0x29,0x7A,0x4D,0x36,0xB7,0x45,0xB7,0x58,0xF5,0x28,0x8E,0xDA,0x31,0x69,0x77,0x7B,0x98,0x73,0x5F,0xEA,0x1A,0xF6,0x1E,0x99,0xB3,0x62,0x74,0xB8,0xBA,0x47,0x73,0x4F,0xA7,0xF1,0x0A,0x77,0x4F,0xE4,0x2A,0xEE,0xD5,0x3D,0xCD,0x91,0x86,0x86,0xBB,0xF0,0x8C,0xC8,0x6C,0x9A,0xCE,0xFE,0x1F};
const uint8_t spDIRECTION[] PROGMEM = {0xA5,0x7E,0xBE,0x3C,0x49,0x14,0xAF,0x6E,0xAA,0x52,0x72,0xCD,0x77,0xBA,0x66,0x4A,0x38,0xAC,0xDB,0xE9,0x8A,0x0F,0xB6,0xB0,0xF4,0xAD,0x4B,0x5D,0xDC,0x35,0xED,0xCF,0xF6,0xD4,0xA5,0x68,0xB8,0x85,0xFB,0x53,0xD6,0x90,0x34,0x1E,0x9D,0x6E,0x31,0xF2,0x36,0x9D,0x4A,0x6C,0x91,0xC9,0x47,0x18,0x63,0xD1,0xD8,0x02,0xE8,0xC1,0xCC,0x01,0x63,0x6C,0x45,0x20,0x02,0x1E,0x68,0x45,0x8D,0xAA,0x6E,0xD1,0x69,0x36,0x63,0x69,0x81,0x2D,0x25,0x9A,0xD4,0x23,0x1D,0x5D,0x0B,0xA5,0x7B,0xB4,0x78,0xF9,0xDB,0x7D,0x23,0x18,0xB9,0x58,0x7C,0xFF,0xBB,0xAF,0x19,0xC1,0x54,0x4B,0xF6,0xFF};
const uint8_t spENTER[] PROGMEM = {0xAB,0x18,0xB6,0x39,0xDC,0x5E,0xDD,0xFA,0x96,0xAB,0xE8,0x41,0x24,0xC9,0x17,0xE5,0x0A,0x0C,0x70,0x4C,0x65,0xE9,0x4A,0x37,0xCC,0xE4,0xDE,0xB3,0x6F,0x73,0xA9,0x0D,0x36,0x9C,0x37,0xEF,0xE9,0xCA,0x35,0xA0,0x5A,0xFA,0x94,0xB7,0xD4,0xC4,0x48,0xC9,0x93,0xBF,0xFF,0x07};
const uint8_t spFEET[] PROGMEM = {0x08,0x98,0x31,0x93,0x02,0x1C,0xE0,0x80,0x07,0x5A,0x3E,0x4A,0x28,0x99,0x3F,0x59,0xE9,0xE8,0x4E,0x64,0xFE,0x64,0x67,0xA3,0x98,0x45,0x41,0xB2,0x67,0xF7,0x36,0x4F,0x6A,0x9F,0x9D,0x91,0xB3,0x6E,0xA3,0x7B,0xCA,0x30,0x53,0x95,0x03,0x00,0x00,0x08,0x18,0xD2,0x4D,0x00,0xC7,0x6C,0x6A,0x40,0x00,0x3D,0xAC,0x62,0xE0,0xFF,0x01};
const uint8_t spFROM[] PROGMEM = {0x04,0x18,0x26,0x8D,0x03,0x12,0xF0,0x80,0xAB,0x42,0x57,0x8B,0x61,0x6F,0xAB,0x4C,0xCE,0x2B,0xD2,0xD4,0xDD,0xE2,0x96,0xA7,0xCC,0x72,0xCA,0x93,0xDB,0xEC,0x6A,0xB7,0x73,0x68,0x4B,0xA7,0x61,0xA1,0x6C,0xB6,0xAF,0xF9,0x88,0x47,0x3C,0xFD,0xF3,0xFF};
const uint8_t spGAP[] PROGMEM = {0x0C,0x08,0xDA,0x75,0x2C,0xB3,0x27,0x19,0xBB,0xDD,0xD1,0xB7,0x44,0xE4,0x51,0x73,0x4E,0x3B,0x7A,0x90,0x49,0x2C,0x39,0x75,0x77,0xAD,0x66,0xB6,0xE6,0x56,0xA7,0xAA,0x31,0x25,0x2D,0xD7,0xEC,0x61,0x2E,0x71,0x41,0xA0,0x08,0xE5,0x2E,0x22,0x1B,0x00,0x00,0x01,0x5D,0x85,0x29,0xE0,0x88,0x76,0x05,0x4C,0xF7,0xCE,0x80,0xEE,0x9B,0x29,0xF0,0xFF};
const uint8_t spHOLD[] PROGMEM = {0x08,0x68,0x34,0x5A,0x03,0x06,0x98,0x42,0xCC,0x02,0x23,0x4F,0x7C,0xD6,0x85,0xDA,0xAC,0xAC,0xE2,0xD8,0x32,0x4C,0xD3,0xF2,0x8C,0xF3,0x9C,0xA9,0x4B,0xCF,0x5A,0x51,0x91,0xEE,0x04,0xBA,0xEB,0x55,0xED,0xCB,0x12,0x85,0x6F,0x0A,0xBB,0xCB,0x6B,0xDC,0xE3,0x61,0x0F,0x73,0x65,0x41,0xAB,0x6A,0x69,0xCC,0x95,0x04,0x75,0x93,0xA7,0x35,0x67,0xD3,0x28,0xE3,0x9A,0x56,0x5D,0x85,0x93,0x65,0x68,0xB6,0x74,0x55,0x63,0xE6,0x62,0x6B,0xDC,0x59,0x2D,0x87,0xBB,0x3F,0xF9,0x7F};
const uint8_t spLEFT[] PROGMEM = {0x69,0x1D,0xC0,0xDA,0xCC,0xD3,0xA6,0xB5,0x81,0x68,0xD1,0xF4,0xDA,0xC7,0xD3,0x57,0x6F,0x11,0xDC,0x4B,0x6E,0x73,0x9A,0xE6,0x5D,0x5B,0x72,0xF5,0xED,0xF7,0xD2,0xCE,0x92,0x2C,0x5C,0xEA,0x0D,0x03,0x8A,0x0E,0x25,0xC0,0x74,0xE3,0x12,0xD0,0x80,0x04,0x10,0x90,0x89,0x2B,0x08,0x60,0x8B,0x71,0x0B,0x10,0xA0,0xB5,0xF3,0xFF,0x07};
const uint8_t spMILL[] PROGMEM = {0x66,0x8E,0x8A,0xA2,0xC2,0x93,0xFA,0x29,0x8E,0xB9,0x1B,0x6D,0x4B,0xA6,0x26,0xF9,0xE4,0xD6,0xB7,0xBA,0xD5,0x6A,0xAB,0x4C,0x6B,0xD5,0xC7,0x6B,0x28,0xA4,0xB3,0x8D,0xFB,0xCC,0xB9,0xEC,0x05,0x75,0x97,0x61,0xDE,0xBA,0xE7,0x33,0x5D,0x0D,0x47,0x4D,0x80,0x97,0x78,0x9B,0xC7,0xEA,0xA9,0x62,0xED,0xFC,0xFF};
const uint8_t spUH[] PROGMEM = {0x63,0x2A,0xAC,0x2B,0x8D,0xF7,0xEC,0xF1,0xB6,0xB7,0xDD,0xDD,0xEC,0xC7,0x5A,0x58,0x55,0x39,0xF5,0x9E,0x6B,0x3D,0xD3,0x59,0xB8,0x67,0x39,0xEE,0x8A,0x77,0x7A,0xAB,0x54,0x6F,0xC7,0x4C,0xF6,0x91,0xCF,0xFF,0x03};
const uint8_t spPAST[] PROGMEM = {0x0A,0x88,0x29,0x4C,0x02,0x25,0xAB,0x4E,0xB4,0xCC,0x6B,0x9E,0x22,0x47,0x89,0xF2,0xAA,0x7C,0xEA,0x1A,0xDC,0x3A,0xED,0xCE,0xAD,0x6F,0x77,0x87,0x3B,0xCF,0x7D,0x9C,0xD5,0xBA,0x75,0xEA,0xE2,0x7E,0xB5,0xAB,0x05,0x8D,0x96,0x5C,0xE2,0xCE,0x3E,0x39,0x93,0xCA,0x0D,0x03,0xBE,0x37,0xD5,0x80,0x05,0x3C,0x60,0x01,0x0D,0x00,0x02,0x9E,0xE7,0xB0,0x80,0x00,0xA6,0x5E,0x47,0x40,0x1D,0x4B,0xFF,0x0F};
const uint8_t spPRESS[] PROGMEM = {0x02,0x28,0x31,0x43,0x03,0x25,0xCB,0xBE,0xDC,0x5D,0xED,0x94,0x22,0x0E,0xCE,0x70,0xC9,0xBD,0xF2,0x9C,0xD5,0xBD,0x24,0xEF,0xC9,0xAB,0x77,0xF5,0x92,0x3E,0x27,0x6B,0xA1,0x25,0xD5,0x56,0xDF,0xEC,0x34,0x5D,0xA7,0x94,0xF9,0xEB,0x3B,0xEC,0x69,0xEE,0x75,0x15,0xC0,0x57,0xC1,0x02,0xF8,0x3D,0x5D,0x02,0x1A,0xD0,0x80,0x04,0x28,0x80,0x81,0xFF,0x07};
const uint8_t spRANGE[] PROGMEM = {0x6C,0xE7,0xA5,0xD9,0x33,0xAD,0xAA,0x4D,0xF7,0xC0,0x6C,0x93,0xEA,0x66,0x3F,0x95,0x3A,0xD5,0x79,0xEB,0x62,0x17,0x69,0x0B,0xE7,0xAB,0x29,0x45,0x8A,0x4B,0xBD,0x9E,0xBA,0x17,0x63,0xB7,0x58,0x7D,0xAB,0x5B,0xAD,0x7A,0x94,0x00,0xAB,0x9C,0xB5,0xBB,0x39,0xCC,0xB9,0xAF,0x75,0x4F,0x7B,0x8F,0x10,0xEE,0x69,0x27,0x9C,0x3D,0x93,0xA4,0x79,0x5C,0x7F,0x87,0xB7,0x7B,0xE6,0x30,0x8B,0xE7,0x5F,0xF3,0x54,0xCD,0x92,0xA1,0x75,0xFC,0xC3,0x80,0x51,0x9C,0x24,0x60,0x01,0x01,0x8C,0xEC,0xF4,0xFF};
const uint8_t spSAFE[] PROGMEM = {0x08,0xF8,0x39,0x4C,0x02,0x1A,0xD0,0x80,0x05,0x3C,0x60,0x81,0x95,0x0F,0x15,0xE2,0x6A,0xAB,0x4F,0xD1,0x43,0x8A,0x8A,0xBF,0xB9,0xD5,0xAD,0x57,0x3F,0xAA,0x23,0xBB,0x3F,0x9E,0xCB,0xDC,0xF3,0x99,0x9E,0x5E,0x19,0xCD,0xEB,0x8E,0x79,0x7A,0x43,0x13,0xED,0x39,0x0C,0x18,0x7E,0x5C,0x02,0x12,0x90,0x00,0x07,0x28,0x40,0x81,0xFF,0x07};
const uint8_t spSOUTH[] PROGMEM = {0x08,0xF8,0x2E,0x8C,0x03,0x0C,0xF8,0xB5,0xCD,0x02,0x16,0x50,0xC0,0x6F,0xA5,0x1E,0x50,0xC0,0x37,0xEE,0x23,0x69,0xCA,0x35,0x55,0x57,0xAF,0xA2,0xD8,0x8E,0x16,0x5D,0x7D,0xEB,0xDB,0xDC,0x76,0xF5,0xC9,0x4C,0x95,0x71,0xEF,0x3D,0xCD,0xBD,0x9C,0xC1,0x75,0x95,0x72,0x97,0xFC,0x84,0x3F,0xAA,0xAE,0x31,0xF1,0x2D,0x5E,0x5B,0x72,0x9C,0x62,0xB5,0xF9,0x92,0x8E,0x18,0x93,0xC4,0x04,0x18,0xB2,0x45,0x02,0x1C,0xA0,0x00,0x05,0x28,0x40,0x81,0xFF,0x07};
const uint8_t spTURN[] PROGMEM = {0x01,0x18,0xA9,0xCC,0x02,0x06,0x28,0x4E,0xA9,0x14,0x39,0x25,0x69,0x4B,0xBA,0x5D,0xAE,0xAA,0x84,0x15,0x5A,0xF5,0xBE,0xAB,0x59,0xCF,0x61,0xCE,0x7D,0x6B,0x5B,0x09,0x49,0x76,0xEE,0xB5,0x1E,0xE5,0x69,0x2E,0x44,0xD3,0x9A,0xE6,0x27,0x7C,0x4D,0x09,0xA5,0x47,0xDC,0xF8,0xB9,0xAF,0x7B,0x62,0xB7,0x70,0xE6,0xBE,0x1A,0x54,0x4C,0xB8,0xDD,0xFF,0x03};
const uint8_t spYELLOW[] PROGMEM = {0x69,0xBD,0x56,0x15,0xAC,0x67,0xE5,0xA5,0xCC,0x2B,0x8E,0x82,0xD8,0xD6,0x39,0x9E,0xAE,0x85,0x50,0x37,0x5F,0x7D,0xEB,0x53,0x55,0x1B,0xDE,0xA6,0x6B,0x56,0x5D,0x74,0x47,0x2B,0x77,0x6E,0x75,0x87,0x59,0x95,0xA4,0x76,0x76,0x6B,0xCE,0xA2,0xB3,0x4C,0xF2,0xCF,0xBD,0xED,0xC9,0x54,0xB6,0x52,0x9F,0x7E,0xA5,0xDB,0xC7,0xCA,0x46,0x5D,0x13,0xEF,0xF8,0x84,0x37,0xA8,0xA9,0x0C,0xF2,0xE3,0xBE,0x24,0xC6,0x2B,0x48,0xDF,0xFF,0x03};
void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT);
digitalWrite(MIC_PIN, HIGH);
// prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up
Serial.begin(9600);
Serial.println("If the sketch freezes at radio status, there is something wrong with power or the shield");
Serial.print("Radio status: ");
int result = radio.testConnection();
Serial.println(result,DEC);
Serial.println("Setting radio to its defaults..");
radio.initialize();
radio.setRfPower(0);
radio.frequency(145010);
}
void loop() {
radio.waitForChannel(); // wait for the channel to be empty
radio.setModeTransmit();
delay(100); // wait for PA to come up
voice.say(spKILO); // to change these to the words you would like to say, or a ham radio call sign - uncomment above encoded words
voice.say(spSIX); // more word choices can be found at the talkie github site
voice.say(spALPHA);
voice.say(spTANGO);
voice.say(spVICTOR);
delay(2000);
voice.say(spDANGER);
voice.say(spDANGER);
voice.say(spMOTOR);
voice.say(spIS);
voice.say(spON);
voice.say(spFIRE);
radio.setModeReceive();
delay(10000);
}

View File

@ -1,10 +0,0 @@
name=HamShield
version=1.1.4
author=Morgan Redfield <morgan@enhancedradio.com>, Casey Halverson <casey@enhancedradio.com>
maintainer=Morgan Redfield <morgan@enhancedradio.com>
sentence=A library for use with HamShield by Enhanced Radio Devices.
paragraph=
category=Device Control
url=http://www.hamshield.com
architectures=*
includes=HamShield.h

File diff suppressed because it is too large Load Diff

View File

@ -1,161 +0,0 @@
/*
* Based loosely on I2Cdev by Jeff Rowberg, except for all kludgy bit-banging
*
* Note that while the Radio IC (AU1846) does have an I2C interface, we've found
* it to be a bit buggy. Instead, we are using a secondary interface to communicate
* with it. The secondary interface is a bit of a hybrid between I2C and SPI.
* uses a Chip-Select pin like SPI, but has bi-directional data like I2C. In order
* to deal with this, we bit-bang the interface.
*/
#include "HamShield_comms.h"
uint8_t ncs_pin = nCS;
uint8_t clk_pin = CLK;
uint8_t dat_pin = DAT;
void HSsetPins(uint8_t ncs, uint8_t clk, uint8_t dat) {
ncs_pin = ncs;
clk_pin = clk;
dat_pin = dat;
#if !defined(ARDUINO)
wiringPiSetup();
#endif
pinMode(ncs_pin, OUTPUT);
digitalWrite(ncs_pin, HIGH);
pinMode(clk_pin, OUTPUT);
digitalWrite(clk_pin, HIGH);
pinMode(dat_pin, OUTPUT);
digitalWrite(dat_pin, HIGH);
}
int8_t HSreadBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data)
{
uint16_t b;
uint8_t count = HSreadWord(devAddr, regAddr, &b);
*data = b & (1 << bitNum);
return count;
}
int8_t HSreadBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data)
{
uint8_t count;
uint16_t w;
if ((count = HSreadWord(devAddr, regAddr, &w)) != 0) {
uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
w &= mask;
w >>= (bitStart - length + 1);
*data = w;
}
return count;
}
int8_t HSreadWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data)
{
//return I2Cdev::readWord(devAddr, regAddr, data);
uint8_t temp;
uint16_t temp_dat;
// bitbang for great justice!
*data = 0;
pinMode(dat_pin, OUTPUT);
regAddr = regAddr | (1 << 7);
digitalWrite(devAddr, 0); //PORTC &= ~(1<<1); //devAddr used as chip select
for (int i = 0; i < 8; i++) {
temp = ((regAddr & (0x80 >> i)) != 0);
digitalWrite(clk_pin, 0); //PORTC &= ~(1<<5); //
digitalWrite(dat_pin, temp);
HSdelayMicroseconds(1);
digitalWrite(clk_pin, 1); //PORTC |= (1<<5); //
HSdelayMicroseconds(1);
}
// change direction of dat_pin
pinMode(dat_pin, INPUT); // DDRC &= ~(1<<4); //
for (int i = 15; i >= 0; i--) {
digitalWrite(clk_pin, 0); //PORTC &= ~(1<<5); //
HSdelayMicroseconds(1);
digitalWrite(clk_pin, 1); //PORTC |= (1<<5); //
temp_dat = digitalRead(dat_pin); //((PINC & (1<<4)) != 0);
temp_dat = temp_dat << i;
*data |= temp_dat;
HSdelayMicroseconds(1);
}
digitalWrite(devAddr, 1); //PORTC |= (1<<1);// CS
return 1;
}
bool HSwriteBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data)
{
uint16_t w;
HSreadWord(devAddr, regAddr, &w);
w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum));
return HSwriteWord(devAddr, regAddr, w);
}
bool HSwriteBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data)
{
uint16_t w;
if (HSreadWord(devAddr, regAddr, &w) != 0) {
uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
data <<= (bitStart - length + 1); // shift data into correct position
data &= mask; // zero all non-important bits in data
w &= ~(mask); // zero all important bits in existing word
w |= data; // combine data with existing word
return HSwriteWord(devAddr, regAddr, w);
} else {
return false;
}
}
bool HSwriteWord(uint8_t devAddr, uint8_t regAddr, uint16_t data)
{
//return I2Cdev::writeWord(devAddr, regAddr, data);
uint8_t temp_reg;
uint16_t temp_dat;
//digitalWrite(13, HIGH);
// bitbang for great justice!
pinMode(dat_pin, OUTPUT);
regAddr = regAddr & ~(1 << 7);
digitalWrite(devAddr, 0); // PORTC &= ~(1<<1); //CS
for (int i = 0; i < 8; i++) {
temp_reg = ((regAddr & (0x80 >> i)) != 0);
digitalWrite(clk_pin, 0); //PORTC &= ~(1<<5); //
digitalWrite(dat_pin, regAddr & (0x80 >> i));
HSdelayMicroseconds(1);
digitalWrite(clk_pin, 1); // PORTC |= (1<<5); //
HSdelayMicroseconds(1);
}
for (int i = 0; i < 16; i++) {
temp_dat = ((data & (0x8000 >> i)) != 0);
digitalWrite(clk_pin, 0); //PORTC &= ~(1<<5); //
digitalWrite(dat_pin, temp_dat);
HSdelayMicroseconds(1);
digitalWrite(clk_pin, 1); // PORTC |= (1<<5); //
HSdelayMicroseconds(1);
}
digitalWrite(devAddr, 1); //PORTC |= (1<<1); //CS
return true;
}
// Hardware abstraction
unsigned long HSmillis(){
return millis();
}
void HSdelay(unsigned long ms) {
delay(ms);
}
void HSdelayMicroseconds(unsigned int us) {
delayMicroseconds(us);
}