80 Commits

Author SHA1 Message Date
morgan
0011026567 fix dangermode 2016-04-17 17:19:33 -07:00
morgan
5f363f1537 updating all examples for new library 2016-04-13 19:12:06 -07:00
morgan
3a209d8db4 updating files for HS09 2016-03-24 20:31:17 -07:00
morgan
9111ba5301 changing default power levels of all examples 2016-01-04 19:36:37 -08:00
morgan
c107df93dd made certain library functions private to ensure they aren't improperly called from an arduino sketch 2015-12-15 14:43:57 -08:00
morgan
28f1ff016c switched to standard I2Cdev lib, changed reg 0x44 volume control to remove agc delay 2015-12-10 17:32:18 -08:00
morgan
c97b0801d5 updated HandieTalkie example, change setTxBand I2C writes 2015-12-02 21:07:36 -08:00
morgan
edc78a3858 adding HandyTalkie example 2015-11-23 19:16:56 -08:00
morgan
807617de83 updated for HS05 2015-11-23 08:54:10 -08:00
morgan
a196501f15 updated setting for GPIO voltage, added code to handle special frequencies 2015-09-18 18:04:03 -07:00
Casey Halverson
c679bec886 some additional fixes for serial transceiver
removed old setrx/settx stuff
2015-07-14 20:10:39 -07:00
Casey Halverson
e55cb9f221 added morse out to serial transceiver, fixed some library version issues 2015-07-14 20:05:22 -07:00
Nigel VH
8ab7f97cbd Merge pull request #14 from slepp/rel-jul13
Minor fixups to KISS, now append FCS. Remove 19200 refclk for now.
2015-07-13 21:34:14 -07:00
Stephen Olesen
638369d659 Minor fixups to KISS, now append FCS. Remove 19200 refclk for now. 2015-07-13 21:16:22 -06:00
Nigel VH
e444b4ef4e Merge pull request #13 from slepp/rel-jul13
Early release branch including AFSK/AX25/KISS, PSK and SSTV.
2015-07-13 18:55:20 -07:00
Stephen Olesen
ab7613c8d3 Updated AFSK/AX25 examples for modifications to AFSK library. 2015-07-13 19:01:32 -06:00
Stephen Olesen
a22b814d63 KISS TNC mode for the AX25 stack and example. 2015-07-13 18:55:07 -06:00
Stephen Olesen
45ec01bd31 Rewrite of framing to always be pure frames, no escapes.
Added parser for packets to pretty print them to serial.
Added parser for easier packet handling on receipt.
Moved bitclock timer to outside ISR loop.
2015-07-13 18:53:18 -06:00
Stephen Olesen
4f1c863487 Default refclk now 9600, remove old table and serial debugging. 2015-07-13 18:50:48 -06:00
Stephen Olesen
ed136d6fe9 Merge remote-tracking branch 'upstream/au_updates' into rel-jul13 2015-07-12 16:59:35 -06:00
Stephen Olesen
6cb8ed68d3 Rename for library compatability. 2015-07-11 14:23:03 -06:00
Stephen Olesen
cf93050e52 Updated AFSK with print routine, use new delay line. AX25 receive tune to APRS. 2015-07-10 11:58:37 -06:00
Stephen Olesen
888cf9d9fd Merge remote-tracking branch 'upstream/au_updates' into afsk-au-update 2015-07-09 14:58:58 -06:00
Stephen Olesen
52ac3def7d Finalize merger. 2015-07-09 14:57:22 -06:00
Casey Halverson
f685e88a42 Reference to wiki added 2015-07-06 17:35:43 -07:00
Casey Halverson
5d4efb9a0f Applying license
AGPLv3
2015-07-06 16:55:28 -07:00
Stephen Olesen
6d8813f200 Merge remote-tracking branch 'upstream/master' into afsk 2015-07-06 11:41:05 -06:00
Stephen Olesen
4fb55520ea First round of AX25 receiver. 2015-07-06 11:40:50 -06:00
Nigel VH
26e5aa75a8 Merge pull request #11 from slepp/hs-progmem
Need const on some compilers.
2015-07-05 20:33:53 -07:00
Stephen Olesen
a2778779d0 Need const on some compilers. 2015-07-05 21:19:16 -06:00
Stephen Olesen
1f81215577 Merge remote-tracking branch 'upstream/master' into afsk 2015-07-05 21:08:09 -06:00
Nigel VH
aaee8915b5 Merge pull request #10 from slepp/hs-progmem
Move frequency lookup tables into progmem.
2015-07-05 16:53:16 -07:00
Nigel VH
efca76806c Merge pull request #9 from slepp/id-test
Check for 0x3AC or 0x32C in testConnection().
2015-07-05 16:52:26 -07:00
Stephen Olesen
1afc2c18f9 Remove extraneous pgmspace.h include. 2015-07-05 17:05:55 -06:00
Stephen Olesen
0721456c28 Move frequency lookup tables into progmem. 2015-07-05 17:03:05 -06:00
Stephen Olesen
2eea6db437 Check for 0x3AC or 0x32C in testConnection(). 2015-07-05 16:32:55 -06:00
Stephen Olesen
9bcf52ec64 Update large DDS sine table to use signed integers. 2015-07-05 16:29:27 -06:00
Stephen Olesen
7131e46ff0 Allow refclkOffset to be set on the fly in DDS and the calibration tool. 2015-07-04 18:31:18 -06:00
Stephen Olesen
1c29498e44 Received frequency calculation added. 2015-07-04 16:39:17 -06:00
Stephen Olesen
4af33167a0 Added Crystal Calibration sketch with simple Serial UI. Fixed ddsAccumulator_t type. 2015-07-04 14:13:45 -06:00
Stephen Olesen
7c67a704c3 Use HamShield now, fix refclk rate, increase toggle speed. 2015-07-04 02:17:03 -06:00
Stephen Olesen
ed594d3128 Back to Wire library usage, mistaken commit on changing it. 2015-07-04 00:03:12 -06:00
Stephen Olesen
f30f9003c1 Merge remote-tracking branch 'upstream/master' into afsk 2015-07-03 23:56:00 -06:00
Nigel VH
167c792116 Merge pull request #6 from slepp/master
Move singleton to the initializer to be used by more things later
2015-07-03 22:55:20 -07:00
Stephen Olesen
c708b3703a Merge remote-tracking branch 'upstream/master' into afsk 2015-07-03 23:54:34 -06:00
Nigel VH
1257cb0b4b Merge pull request #3 from slepp/morse-clean
Clean (no whitespace changes) of the Morse table changes.
2015-07-03 22:51:54 -07:00
Stephen Olesen
8ebeabe496 Now using actual radio hardware in AFSK and SSTV. Tuned Tx settling timers. 2015-07-03 21:21:51 -06:00
Stephen Olesen
208087693d Pretty basic SSTV transmitter in Martin-1. Sends a static image. 2015-07-03 15:24:17 -06:00
Stephen Olesen
acc4aebe03 Add calculators for frequency steps. Accumulator has a typedef now. Optimize tick. 2015-07-03 15:23:39 -06:00
Stephen Olesen
5fd0fdf154 Merge branch 'master' into afsk 2015-07-02 21:32:54 -06:00
Stephen Olesen
1aa7f7d224 Merge remote-tracking branch 'upstream/master' 2015-07-02 21:32:24 -06:00
Stephen Olesen
28248365c8 Added QPSK63. Set both sketches to run on either pin 3 or 11. 2015-07-02 21:27:12 -06:00
Stephen Olesen
26ffcd332b Faster reference clock rate (using pin 3), skip outer loop to slow PSK. 2015-07-02 19:58:54 -06:00
Stephen Olesen
77a8c62b78 Correct Pin 3 output to scale to the reduced comparator size. 2015-07-02 19:57:32 -06:00
Stephen Olesen
6ff2791963 Change to the waveform shaping trying to reduce IMD. 2015-07-02 19:31:16 -06:00
Stephen Olesen
7db28bff0e Change DDS to using signed integers to try to keep our DC bias averaged out. 2015-07-02 19:30:53 -06:00
Stephen Olesen
437e750e76 Rough PSK31 example, constant transmit of a string. 2015-07-02 18:06:57 -06:00
Stephen Olesen
2152100873 Change amplitude scaling. Go back to refclk for ICR1. Added phase changes. 2015-07-02 18:04:12 -06:00
Stephen Olesen
0e9a549f56 Fix a compile error. Add a quick callsign appending string method. 2015-07-02 02:38:28 -06:00
Stephen Olesen
4a8e9c69e6 Workaround for lockup on AFSK/DDS startup when using the Wire library. 2015-07-02 01:32:00 -06:00
Stephen Olesen
8e8c88f67c Stop transmitting (in a hackish way) when the TX is done. 2015-07-02 01:31:36 -06:00
Stephen Olesen
13be6810f1 Modified to initialize and try to use the radio. 2015-07-02 01:26:47 -06:00
Stephen Olesen
80a1741575 Preliminary addition of static memory allocations for packet buffers.
Fixed(?) DDS frequency calculation on-chip.
2015-07-02 01:24:55 -06:00
Stephen Olesen
d2dc9adbc0 Remove ISR from HamShield, add DDS header. 2015-07-01 20:47:56 -06:00
Stephen Olesen
429e645ad2 Example for AFSK sending (AX25 format) added. DDS updated to a slower clock rate again. 2015-07-01 20:30:49 -06:00
Stephen Olesen
5689393c11 Replace local DDS with the DDS class. 2015-07-01 18:25:59 -06:00
Stephen Olesen
660fe0c602 Corrected the duration calculation on fixed DDS length. 2015-07-01 18:05:17 -06:00
Stephen Olesen
120442533d Added DDS sample. Fixed pin 11 PWM output, now default (3 works better). 2015-07-01 17:56:40 -06:00
Stephen Olesen
016ad2398a Added a define to use pin 3 for PWM, instead of the new default pin 11. 2015-07-01 15:01:55 -06:00
Stephen Olesen
8f2115adbc Add some comments. 2015-07-01 14:54:22 -06:00
Stephen Olesen
2f4d17e4ed Fixed up the duration timers, clockTick needs a cleanup. 2015-07-01 14:42:20 -06:00
Stephen Olesen
31eb465ebf Allow for high idle duty cycle when output is 'off', amplitude adjustments. 2015-07-01 14:27:10 -06:00
Stephen Olesen
1117542411 Created generic DDS class for tone generation, update AFSK to start the right timers. 2015-07-01 14:04:20 -06:00
Stephen Olesen
55c10c503b Some spacing, added header length minimum. 2015-06-30 20:32:28 -06:00
Stephen Olesen
9b2987de08 Initial import of the main code from https://github.com/slepp/AX25
Partially functional, but no accuracy tests complete yet.
2015-06-30 19:22:46 -06:00
Stephen Olesen
6a5815d9b5 Move singleton to the initializer to be used by more things later. Made public. 2015-06-30 16:37:55 -06:00
Stephen Olesen
0fd2d484e1 Added back in the tone waits in morseOut. 2015-06-30 16:03:21 -06:00
Stephen Olesen
fc09429133 Alter morseOut to use a for loop and clearer dit/dah timing in the tone.
Back up to 1000Hz tones.
2015-06-30 15:30:06 -06:00
Stephen Olesen
1c7dbfc4b6 Correct the return time on morseLookup to be more obvious it's binary. 2015-06-30 15:17:07 -06:00
Stephen Olesen
7dff74d780 Clean version of the Morse binary format/table and lookup functions. 2015-06-30 15:13:55 -06:00
51 changed files with 33183 additions and 2414 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_ */

File diff suppressed because it is too large Load Diff

View File

@@ -8,17 +8,24 @@
#ifndef _HAMSHIELD_H_ #ifndef _HAMSHIELD_H_
#define _HAMSHIELD_H_ #define _HAMSHIELD_H_
#include "I2Cdev_rda.h" //#include "I2Cdev_rda.h"
//#include "I2Cdev.h"
#include "HamShield_comms.h"
#include "SimpleFIFO.h"
#include "AFSK.h"
#include "DDS.h"
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
// HamShield constants // HamShield constants
#define HAMSHIELD_MORSE_DOT 100 // Morse code dot length (smaller is faster WPM) #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_MORSE_BUFFER_SIZE 80 // Char buffer size for morse code text
#define HAMSHIELD_AUX_BUTTON 5 // Pin assignment for AUX button #define HAMSHIELD_AUX_BUTTON 2 // Pin assignment for AUX button
#define HAMSHIELD_PWM_PIN 11 // Pin assignment for PWM output #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_EMPTY_CHANNEL_RSSI -110 // Default threshold where channel is considered "clear"
#define HAMSHIELD_AFSK_RX_FIFO_LEN 16
// button modes // button modes
#define PTT_MODE 1 #define PTT_MODE 1
#define RESET_MODE 2 #define RESET_MODE 2
@@ -181,7 +188,7 @@
#define A1846S_VOX_FLAG_BIT 0 // vox out from dsp #define A1846S_VOX_FLAG_BIT 0 // vox out from dsp
// Bitfields for A1846S_RSSI_REG // Bitfields for A1846S_RSSI_REG
#define A1846S_RSSI_BIT 15 // RSSI readings <9:0> #define A1846S_RSSI_BIT 15 // RSSI readings <7:0>
#define A1846S_RSSI_LENGTH 8 #define A1846S_RSSI_LENGTH 8
// Bitfields for A1846S_VSSI_REG // Bitfields for A1846S_VSSI_REG
@@ -252,6 +259,9 @@
class HamShield { class HamShield {
public: public:
// public singleton for ISRs to reference
static HamShield *sHamShield; // HamShield singleton, used for ISRs mostly
HamShield(); HamShield();
HamShield(uint8_t address); HamShield(uint8_t address);
@@ -262,245 +272,205 @@ class HamShield {
uint16_t readCtlReg(); uint16_t readCtlReg();
void softReset(); void softReset();
// center frequency // restrictions control
void setFrequency(uint32_t freq_khz); void dangerMode();
uint32_t getFrequency(); void safeMode();
// band bool frequency(uint32_t freq_khz);
// 00 - 400-520MHz uint32_t getFrequency();
// 10 - 200-260MHz
// 11 - 134-174MHz
void setBand(uint16_t band);
uint16_t getBand();
void setUHF();
void setVHF();
void setNoFilters();
bool frequency(uint32_t freq_khz);
// xtal frequency (kHz)
// 12-14MHz crystal: this reg is set to crystal freq_khz
// 24-28MHz crystal: this reg is set to crystal freq_khz / 2
void setXtalFreq(uint16_t freq_kHz);
uint16_t getXtalFreq();
// adclk frequency (kHz)
// 12-14MHz crystal: this reg is set to crystal freq_khz / 2
// 24-28MHz crystal: this reg is set to crystal freq_khz / 4
void setAdcClkFreq(uint16_t freq_kHz);
uint16_t getAdcClkFreq();
// clk mode
// 12-14MHz: set to 1
// 24-28MHz: set to 0
void setClkMode(bool LFClk);
bool getClkMode();
// clk example
// 12.8MHz clock
// A1846S_XTAL_FREQ_REG[15:0]= xtal_freq<15:0>=12.8*1000=12800
// A1846S_ADCLK_FREQ_REG[12:0] =adclk_freq<15:0>=(12.8/2)*1000=6400
// A1846S_CLK_MODE_REG[0]= clk_mode =1
// TX/RX control
// channel mode
// 11 - 25kHz channel
// 00 - 12.5kHz channel
// 10,01 - reserved
void setChanMode(uint16_t mode);
uint16_t getChanMode();
// choose tx or rx
void setTX(bool on_noff);
bool getTX();
void setRX(bool on_noff);
bool getRX();
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
// set tx source
// 00 - Mic source
// 01 - sine source from tone2
// 10 - tx code from GPIO1 code_in (gpio1<1:0> must be set to 01)
// 11 - no tx source
void setTxSource(uint16_t tx_source);
void setTxSourceMic();
void setTxSourceTone1();
void setTxSourceTone2();
void setTxSourceTones();
void setTxSourceNone();
uint16_t getTxSource();
// set PA_bias voltage
// 000000: 1.01V
// 000001:1.05V
// 000010:1.09V
// 000100: 1.18V
// 001000: 1.34V
// 010000: 1.68V
// 100000: 2.45V
// 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 setInnerCtcssMode();
void setInnerCdcssMode();
void setOuterCtcssMode();
void setOuterCdcssMode();
void disableCtcssCdcss();
// Ctcss_sel
// 1 = ctcss_cmp/cdcss_cmp out via gpio
// 0 = ctcss/cdcss sdo out vio gpio
void setCtcssSel(bool cmp_nsdo);
bool getCtcssSel();
// Cdcss_sel
// 1 = long (24 bit) code
// 0 = short(23 bit) code
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();
// 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 // channel mode
void setSQOn(); // 11 - 25kHz channel
void setSQOff(); // 00 - 12.5kHz channel
bool getSQState(); // 10,01 - reserved
void setChanMode(uint16_t mode);
// SQ threshold uint16_t getChanMode();
void setSQHiThresh(uint16_t sq_hi_threshold); // Sq detect high th, rssi_cmp will be 1 when rssi>th_h_sq, unit 1/8dB
uint16_t getSQHiThresh(); void setModeTransmit(); // turn off rx, turn on tx
void setSQLoThresh(uint16_t sq_lo_threshold); // Sq detect low th, rssi_cmp will be 0 when rssi<th_l_sq && time delay meet, unit 1/8 dB void setModeReceive(); // turn on rx, turn off tx
uint16_t getSQLoThresh(); void setModeOff(); // turn off rx, turn off tx, set pwr_dwn bit
// SQ out select // set tx source
void setSQOutSel(); // 00 - Mic source
void clearSQOutSel(); // 01 - sine source from tone2
bool getSQOutSel(); // 10 - tx code from GPIO1 code_in (gpio1<1:0> must be set to 01)
// 11 - no tx source
// VOX void setTxSource(uint16_t tx_source);
void setVoxOn(); void setTxSourceMic();
void setVoxOff(); void setTxSourceTone1();
bool getVoxOn(); void setTxSourceTone2();
void setTxSourceTones();
// Vox Threshold void setTxSourceNone();
void setVoxOpenThresh(uint16_t vox_open_thresh); // When vssi > th_h_vox, then vox will be 1(unit mV ) uint16_t getTxSource();
uint16_t getVoxOpenThresh();
void setVoxShutThresh(uint16_t vox_shut_thresh); // When vssi < th_l_vox && time delay meet, then vox will be 0 (unit mV ) // PA bias voltage is unused (maybe remove this)
uint16_t getVoxShutThresh(); // set PA_bias voltage
// 000000: 1.01V
// Tail Noise // 000001:1.05V
void enableTailNoiseElim(); // 000010:1.09V
void disableTailNoiseElim(); // 000100: 1.18V
bool getTailNoiseElimEnabled(); // 001000: 1.34V
// 010000: 1.68V
// tail noise shift select // 100000: 2.45V
// Select ctcss phase shift when use tail eliminating function when TX // 1111111:3.13V
// 00 = 120 degree shift void setPABiasVoltage(uint16_t voltage);
// 01 = 180 degree shift uint16_t getPABiasVoltage();
// 10 = 240 degree shift
// 11 = reserved // Subaudio settings
void setShiftSelect(uint16_t shift_sel);
uint16_t getShiftSelect(); // Ctcss/cdcss mode sel
// x00=disable,
// DTMF // 001=inner ctcss en,
void setDTMFC0(uint16_t freq); // 010= inner cdcss en
uint16_t getDTMFC0(); // 101= outer ctcss en,
void setDTMFC1(uint16_t freq); // 110=outer cdcss en
uint16_t getDTMFC1(); // others =disable
void setDTMFC2(uint16_t freq); void setCtcssCdcssMode(uint16_t mode);
uint16_t getDTMFC2(); uint16_t getCtcssCdcssMode();
void setDTMFC3(uint16_t freq); void setInnerCtcssMode();
uint16_t getDTMFC3(); void setInnerCdcssMode();
void setDTMFC4(uint16_t freq); void setOuterCtcssMode();
uint16_t getDTMFC4(); void setOuterCdcssMode();
void setDTMFC5(uint16_t freq); void disableCtcssCdcss();
uint16_t getDTMFC5();
void setDTMFC6(uint16_t freq); // Ctcss_sel
uint16_t getDTMFC6(); // 1 = ctcss_cmp/cdcss_cmp out via gpio
void setDTMFC7(uint16_t freq); // 0 = ctcss/cdcss sdo out vio gpio
uint16_t getDTMFC7(); void setCtcssSel(bool cmp_nsdo);
bool getCtcssSel();
// TX FM deviation
void setFMVoiceCssDeviation(uint16_t deviation); // Cdcss_sel
uint16_t getFMVoiceCssDeviation(); // 1 = long (24 bit) code
void setFMCssDeviation(uint16_t deviation); // 0 = short(23 bit) code
uint16_t getFMCssDeviation(); void setCdcssSel(bool long_nshort);
bool getCdcssSel();
// RX voice range // Cdcss neg_det_en
void setVolume1(uint16_t volume); void enableCdcssNegDet();
uint16_t getVolume1(); void disableCdcssNegDet();
void setVolume2(uint16_t volume); bool getCdcssNegDetEnabled();
uint16_t getVolume2();
// Cdcss pos_det_en
// GPIO void enableCdcssPosDet();
void setGpioMode(uint16_t gpio, uint16_t mode); void disableCdcssPosDet();
void setGpioHiZ(uint16_t gpio); bool getCdcssPosDetEnabled();
void setGpioFcn(uint16_t gpio);
void setGpioLow(uint16_t gpio); // css_det_en
void setGpioHi(uint16_t gpio); void enableCssDet();
uint16_t getGpioMode(uint16_t gpio); void disableCssDet();
bool getCssDetEnabled();
// Int
void enableInterrupt(uint16_t interrupt); // ctcss freq
void disableInterrupt(uint16_t interrupt); void setCtcss(float freq);
bool getInterruptEnabled(uint16_t interrupt); void setCtcssFreq(uint16_t freq);
uint16_t getCtcssFreq();
// ST mode void setCtcssFreqToStandard(); // freq must be 134.4Hz for standard cdcss mode
void setStMode(uint16_t mode);
uint16_t getStMode(); // cdcss codes
void setStFullAuto(); void setCdcssCode(uint16_t code);
void setStRxAutoTxManu(); uint16_t getCdcssCode();
void setStFullManu();
// SQ
// Pre-emphasis, De-emphasis filter void setSQOn();
void bypassPreDeEmph(); void setSQOff();
void usePreDeEmph(); bool getSQState();
bool getPreDeEmphEnabled();
// SQ threshold
// Read Only Status Registers void setSQHiThresh(uint16_t sq_hi_threshold); // Sq detect high th, rssi_cmp will be 1 when rssi>th_h_sq, unit 1/8dB
int16_t readRSSI(); uint16_t getSQHiThresh();
uint16_t readVSSI(); void setSQLoThresh(uint16_t sq_lo_threshold); // Sq detect low th, rssi_cmp will be 0 when rssi<th_l_sq && time delay meet, unit 1/8 dB
uint16_t readDTMFIndex(); // may want to split this into two (index1 and index2) uint16_t getSQLoThresh();
uint16_t readDTMFCode();
// SQ out select
void setSQOutSel();
void clearSQOutSel();
bool getSQOutSel();
// VOX
void setVoxOn();
void setVoxOff();
bool getVoxOn();
// Vox Threshold
void setVoxOpenThresh(uint16_t vox_open_thresh); // When vssi > th_h_vox, then vox will be 1(unit mV )
uint16_t getVoxOpenThresh();
void setVoxShutThresh(uint16_t vox_shut_thresh); // When vssi < th_l_vox && time delay meet, then vox will be 0 (unit mV )
uint16_t getVoxShutThresh();
// Tail Noise
void enableTailNoiseElim();
void disableTailNoiseElim();
bool getTailNoiseElimEnabled();
// tail noise shift select
// Select ctcss phase shift when use tail eliminating function when TX
// 00 = 120 degree shift
// 01 = 180 degree shift
// 10 = 240 degree shift
// 11 = reserved
void setShiftSelect(uint16_t shift_sel);
uint16_t getShiftSelect();
// DTMF
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();
// TX FM deviation
void setFMVoiceCssDeviation(uint16_t deviation);
uint16_t getFMVoiceCssDeviation();
void setFMCssDeviation(uint16_t deviation);
uint16_t getFMCssDeviation();
// RX voice range
void setVolume1(uint16_t volume);
uint16_t getVolume1();
void setVolume2(uint16_t volume);
uint16_t getVolume2();
// GPIO
void setGpioMode(uint16_t gpio, uint16_t mode);
void setGpioHiZ(uint16_t gpio);
void setGpioFcn(uint16_t gpio);
void setGpioLow(uint16_t gpio);
void setGpioHi(uint16_t gpio);
uint16_t getGpioMode(uint16_t gpio);
uint16_t getGpios();
// Int
void enableInterrupt(uint16_t interrupt);
void disableInterrupt(uint16_t interrupt);
bool getInterruptEnabled(uint16_t interrupt);
// ST mode
void setStMode(uint16_t mode);
uint16_t getStMode();
void setStFullAuto();
void setStRxAutoTxManu();
void setStFullManu();
// Pre-emphasis, De-emphasis filter
void bypassPreDeEmph();
void usePreDeEmph();
bool getPreDeEmphEnabled();
// Read Only Status Registers
int16_t readRSSI();
uint16_t readVSSI();
uint16_t readDTMFIndex(); // may want to split this into two (index1 and index2)
uint16_t readDTMFCode();
// set output power of radio // set output power of radio
void setRfPower(uint8_t pwr); void setRfPower(uint8_t pwr);
@@ -511,11 +481,6 @@ class HamShield {
bool setMURSChannel(uint8_t channel); bool setMURSChannel(uint8_t channel);
bool setWXChannel(uint8_t channel); bool setWXChannel(uint8_t channel);
uint8_t scanWXChannel(); uint8_t scanWXChannel();
// restrictions control
void dangerMode();
void safeMode();
// utilities // utilities
uint32_t scanMode(uint32_t start,uint32_t stop, uint8_t speed, uint16_t step, uint16_t threshold); uint32_t scanMode(uint32_t start,uint32_t stop, uint8_t speed, uint16_t step, uint16_t threshold);
@@ -525,34 +490,68 @@ class HamShield {
void buttonMode(uint8_t mode); void buttonMode(uint8_t mode);
static void isr_ptt(); static void isr_ptt();
static void isr_reset(); static void isr_reset();
void morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]); void morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]);
char morseLookup(char letter); uint8_t morseLookup(char letter);
bool waitForChannel(long timeout, long breakwindow, int setRSSI); bool waitForChannel(long timeout, long breakwindow, int setRSSI);
void SSTVVISCode(int code); void SSTVVISCode(int code);
void SSTVTestPattern(int code); void SSTVTestPattern(int code);
void toneWait(uint16_t freq, long timer); void toneWait(uint16_t freq, long timer);
void toneWaitU(uint16_t freq, long timer); void toneWaitU(uint16_t freq, long timer);
bool parityCalc(int code); bool parityCalc(int code);
// void AFSKOut(char buffer[80]); // void AFSKOut(char buffer[80]);
// AFSK routines
bool AFSKStart();
bool AFSKEnabled() { return afsk.enabled(); }
bool AFSKStop();
bool AFSKOut(const char *);
class AFSK afsk;
private: private:
uint8_t devAddr; uint8_t devAddr;
uint16_t radio_i2c_buf[4]; uint16_t radio_i2c_buf[4];
int pwr_control_pin; bool tx_active;
bool rx_active;
uint32_t radio_frequency; uint32_t radio_frequency;
uint32_t FRS[]; uint32_t FRS[];
uint32_t GMRS[]; uint32_t GMRS[];
uint32_t MURS[]; uint32_t MURS[];
uint32_t WX[]; uint32_t WX[];
static HamShield *sHamShield; // HamShield singleton, used for ISRs mostly
// private utility functions
// int8_t A1846S::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout); // these functions should not be called in the Arduino sketch
// int8_t A1846S::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout); // just use the above public functions to do everything
// int8_t A1846S::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout);
// int8_t A1846S::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout); void setFrequency(uint32_t freq_khz);
// bool A1846S::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data); void setTxBand2m();
// bool A1846S::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data); void setTxBand1_2m();
void setTxBand70cm();
// xtal frequency (kHz)
// 12-14MHz crystal: this reg is set to crystal freq_khz
// 24-28MHz crystal: this reg is set to crystal freq_khz / 2
void setXtalFreq(uint16_t freq_kHz);
uint16_t getXtalFreq();
// adclk frequency (kHz)
// 12-14MHz crystal: this reg is set to crystal freq_khz / 2
// 24-28MHz crystal: this reg is set to crystal freq_khz / 4
void setAdcClkFreq(uint16_t freq_kHz);
uint16_t getAdcClkFreq();
// clk mode
// 12-14MHz: set to 1
// 24-28MHz: set to 0
void setClkMode(bool LFClk);
bool getClkMode();
// choose tx or rx
void setTX(bool on_noff);
bool getTX();
void setRX(bool on_noff);
bool getRX();
}; };
#endif /* _HAMSHIELD_H_ */ #endif /* _HAMSHIELD_H_ */

168
HamShield_comms.cpp Normal file
View File

@@ -0,0 +1,168 @@
/*
* Based loosely on I2Cdev by Jeff Rowberg, except for all kludgy bit-banging
*/
#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)
{
//return I2Cdev::readWord(devAddr, regAddr, data);
uint8_t temp;
uint16_t temp_dat;
// bitbang for great justice!
*data = 0;
cli();
DDRC |= ((1<<5) | (1<<4)); // set direction to output
sei();
regAddr = regAddr | (1 << 7);
cli();
PORTC &= ~(1<<1); //digitalWrite(nSEN, 0);
sei();
for (int i = 0; i < 8; i++) {
temp = ((regAddr & (0x80 >> i)) != 0);
cli();
PORTC &= ~(1<<5); //digitalWrite(CLK, 0);
sei();
//digitalWrite(DAT, regAddr & (0x80 >> i));
temp = (PORTC & ~(1<<4)) + (temp << 4);
cli();
PORTC = temp;
sei();
delayMicroseconds(9);
cli();
PORTC |= (1<<5); //digitalWrite(CLK, 1);
sei();
delayMicroseconds(9);
}
// change direction of DAT
cli();
DDRC &= ~(1<<4); //pinMode(DAT, INPUT);
sei();
for (int i = 15; i >= 0; i--) {
cli();
PORTC &= ~(1<<5); //digitalWrite(CLK, 0);
sei();
delayMicroseconds(9);
cli();
PORTC |= (1<<5); //digitalWrite(CLK, 1);
sei();
cli();
temp_dat = ((PINC & (1<<4)) != 0);
sei();
temp_dat = temp_dat << i;
*data |= temp_dat; // digitalRead(DAT);
delayMicroseconds(9);
}
cli();
PORTC |= (1<<1);//digitalWrite(nSEN, 1);
DDRC &= ~((1<<5) | (1<<4)); // set direction all input (for ADC)
sei();
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!
cli();
DDRC |= ((1<<5) | (1<<4)); // set direction all output
//PORTC |= (1<<5) & (1<<4);
sei();
regAddr = regAddr & ~(1 << 7);
cli();
PORTC &= ~(1<<1); //digitalWrite(nSEN, 0);
sei();
for (int i = 0; i < 8; i++) {
temp_reg = ((regAddr & (0x80 >> i)) != 0);
cli();
PORTC &= ~(1<<5); //digitalWrite(CLK, 0);
sei();
//digitalWrite(DAT, regAddr & (0x80 >> i));
temp_reg = (PORTC & ~(1<<4)) + (temp_reg << 4);
cli();
PORTC = temp_reg;
sei();
delayMicroseconds(8);
cli();
PORTC |= (1<<5); //digitalWrite(CLK, 1);
sei();
delayMicroseconds(10);
}
for (int i = 0; i < 16; i++) {
temp_dat = ((data & (0x8000 >> i)) != 0);
cli();
PORTC &= ~(1<<5); //digitalWrite(CLK, 0);
sei();
//digitalWrite(DAT, data & (0x80000 >> i));
temp_reg = (PORTC & ~(1<<4)) + (temp_dat << 4);
cli();
PORTC = temp_reg;
sei();
delayMicroseconds(7);
cli();
PORTC |= (1<<5); //digitalWrite(CLK, 1);
sei();
delayMicroseconds(10);
}
cli();
PORTC |= (1<<1); //digitalWrite(nSEN, 1);
DDRC &= ~((1<<5) | (1<<4)); // set direction to input for ADC
sei();
return true;
}

22
HamShield_comms.h Normal file
View File

@@ -0,0 +1,22 @@
#ifndef _HAMSHIELD_COMMS_H_
#define _HAMSHIELD_COMMS_H_
#include "Arduino.h"
//#include "I2Cdev.h"
#define nSEN A1
#define CLK A5
#define DAT A4
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);
int8_t HSreadWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data);
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);
#endif /* _HAMSHIELD_COMMS_H_ */

File diff suppressed because it is too large Load Diff

View File

@@ -1,269 +0,0 @@
// I2Cdev library collection - Main I2C device class header file
// Abstracts bit and byte I2C R/W functions into a convenient class
// 6/9/2012 by Jeff Rowberg <jeff@rowberg.net>
//
// Changelog:
// 2013-05-06 - add Francesco Ferrara's Fastwire v0.24 implementation with small modifications
// 2013-05-05 - fix issue with writing bit values to words (Sasquatch/Farzanegan)
// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire
// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation
// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums)
// 2011-10-03 - added automatic Arduino version detection for ease of use
// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications
// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x)
// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default
// 2011-08-02 - added support for 16-bit registers
// - fixed incorrect Doxygen comments on some methods
// - added timeout value for read operations (thanks mem @ Arduino forums)
// 2011-07-30 - changed read/write function structures to return success or byte counts
// - made all methods static for multi-device memory savings
// 2011-07-28 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2013 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#ifndef _I2CDEV_RDA_H_
#define _I2CDEV_RDA_H_
// -----------------------------------------------------------------------------
// I2C interface implementation setting
// -----------------------------------------------------------------------------
#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE
//#define I2CDEV_IMPLEMENTATION I2CDEV_BUILTIN_FASTWIRE
// comment this out if you are using a non-optimal IDE/implementation setting
// but want the compiler to shut up about it
#define I2CDEV_IMPLEMENTATION_WARNINGS
// -----------------------------------------------------------------------------
// I2C interface implementation options
// -----------------------------------------------------------------------------
#define I2CDEV_ARDUINO_WIRE 1 // Wire object from Arduino
#define I2CDEV_BUILTIN_NBWIRE 2 // Tweaked Wire object from Gene Knight's NBWire project
// ^^^ NBWire implementation is still buggy w/some interrupts!
#define I2CDEV_BUILTIN_FASTWIRE 3 // FastWire object from Francesco Ferrara's project
#define I2CDEV_I2CMASTER_LIBRARY 4 // I2C object from DSSCircuits I2C-Master Library at https://github.com/DSSCircuits/I2C-Master-Library
// -----------------------------------------------------------------------------
// Arduino-style "Serial.print" debug constant (uncomment to enable)
// -----------------------------------------------------------------------------
//#define I2CDEV_SERIAL_DEBUG
#ifdef ARDUINO
#if ARDUINO < 100
#include "WProgram.h"
#else
#include "Arduino.h"
#endif
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
#include <Wire.h>
#endif
#if I2CDEV_IMPLEMENTATION == I2CDEV_I2CMASTER_LIBRARY
#include <I2C.h>
#endif
#endif
// 1000ms default read timeout (modify with "I2Cdev::readTimeout = [ms];")
#define I2CDEV_DEFAULT_READ_TIMEOUT 1000
class I2Cdev {
public:
I2Cdev();
static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data);
static uint16_t readTimeout;
};
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
//////////////////////
// FastWire 0.24
// This is a library to help faster programs to read I2C devices.
// Copyright(C) 2012
// Francesco Ferrara
//////////////////////
/* Master */
#define TW_START 0x08
#define TW_REP_START 0x10
/* Master Transmitter */
#define TW_MT_SLA_ACK 0x18
#define TW_MT_SLA_NACK 0x20
#define TW_MT_DATA_ACK 0x28
#define TW_MT_DATA_NACK 0x30
#define TW_MT_ARB_LOST 0x38
/* Master Receiver */
#define TW_MR_ARB_LOST 0x38
#define TW_MR_SLA_ACK 0x40
#define TW_MR_SLA_NACK 0x48
#define TW_MR_DATA_ACK 0x50
#define TW_MR_DATA_NACK 0x58
#define TW_OK 0
#define TW_ERROR 1
class Fastwire {
private:
static boolean waitInt();
public:
static void setup(int khz, boolean pullup);
static byte beginTransmission(byte device);
static byte write(byte value);
static byte writeBuf(byte device, byte address, byte *data, byte num);
static byte readBuf(byte device, byte address, byte *data, byte num);
static void reset();
static byte stop();
};
#endif
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
// NBWire implementation based heavily on code by Gene Knight <Gene@Telobot.com>
// Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html
// Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html
#define NBWIRE_BUFFER_LENGTH 32
class TwoWire {
private:
static uint8_t rxBuffer[];
static uint8_t rxBufferIndex;
static uint8_t rxBufferLength;
static uint8_t txAddress;
static uint8_t txBuffer[];
static uint8_t txBufferIndex;
static uint8_t txBufferLength;
// static uint8_t transmitting;
static void (*user_onRequest)(void);
static void (*user_onReceive)(int);
static void onRequestService(void);
static void onReceiveService(uint8_t*, int);
public:
TwoWire();
void begin();
void begin(uint8_t);
void begin(int);
void beginTransmission(uint8_t);
//void beginTransmission(int);
uint8_t endTransmission(uint16_t timeout=0);
void nbendTransmission(void (*function)(int)) ;
uint8_t requestFrom(uint8_t, int, uint16_t timeout=0);
//uint8_t requestFrom(int, int);
void nbrequestFrom(uint8_t, int, void (*function)(int));
void send(uint8_t);
void send(uint8_t*, uint8_t);
//void send(int);
void send(char*);
uint8_t available(void);
uint8_t receive(void);
void onReceive(void (*)(int));
void onRequest(void (*)(void));
};
#define TWI_READY 0
#define TWI_MRX 1
#define TWI_MTX 2
#define TWI_SRX 3
#define TWI_STX 4
#define TW_WRITE 0
#define TW_READ 1
#define TW_MT_SLA_NACK 0x20
#define TW_MT_DATA_NACK 0x30
#define CPU_FREQ 16000000L
#define TWI_FREQ 100000L
#define TWI_BUFFER_LENGTH 32
/* TWI Status is in TWSR, in the top 5 bits: TWS7 - TWS3 */
#define TW_STATUS_MASK (_BV(TWS7)|_BV(TWS6)|_BV(TWS5)|_BV(TWS4)|_BV(TWS3))
#define TW_STATUS (TWSR & TW_STATUS_MASK)
#define TW_START 0x08
#define TW_REP_START 0x10
#define TW_MT_SLA_ACK 0x18
#define TW_MT_SLA_NACK 0x20
#define TW_MT_DATA_ACK 0x28
#define TW_MT_DATA_NACK 0x30
#define TW_MT_ARB_LOST 0x38
#define TW_MR_ARB_LOST 0x38
#define TW_MR_SLA_ACK 0x40
#define TW_MR_SLA_NACK 0x48
#define TW_MR_DATA_ACK 0x50
#define TW_MR_DATA_NACK 0x58
#define TW_ST_SLA_ACK 0xA8
#define TW_ST_ARB_LOST_SLA_ACK 0xB0
#define TW_ST_DATA_ACK 0xB8
#define TW_ST_DATA_NACK 0xC0
#define TW_ST_LAST_DATA 0xC8
#define TW_SR_SLA_ACK 0x60
#define TW_SR_ARB_LOST_SLA_ACK 0x68
#define TW_SR_GCALL_ACK 0x70
#define TW_SR_ARB_LOST_GCALL_ACK 0x78
#define TW_SR_DATA_ACK 0x80
#define TW_SR_DATA_NACK 0x88
#define TW_SR_GCALL_DATA_ACK 0x90
#define TW_SR_GCALL_DATA_NACK 0x98
#define TW_SR_STOP 0xA0
#define TW_NO_INFO 0xF8
#define TW_BUS_ERROR 0x00
//#define _MMIO_BYTE(mem_addr) (*(volatile uint8_t *)(mem_addr))
//#define _SFR_BYTE(sfr) _MMIO_BYTE(_SFR_ADDR(sfr))
#ifndef sbi // set bit
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#endif // sbi
#ifndef cbi // clear bit
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#endif // cbi
extern TwoWire Wire;
#endif // I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
#endif /* _I2CDEV_RDA_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_ */

661
LICENSE Normal file
View File

@@ -0,0 +1,661 @@
GNU AFFERO GENERAL PUBLIC LICENSE
Version 3, 19 November 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU Affero General Public License is a free, copyleft license for
software and other kinds of works, specifically designed to ensure
cooperation with the community in the case of network server software.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
our General Public Licenses are intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
Developers that use our General Public Licenses protect your rights
with two steps: (1) assert copyright on the software, and (2) offer
you this License which gives you legal permission to copy, distribute
and/or modify the software.
A secondary benefit of defending all users' freedom is that
improvements made in alternate versions of the program, if they
receive widespread use, become available for other developers to
incorporate. Many developers of free software are heartened and
encouraged by the resulting cooperation. However, in the case of
software used on network servers, this result may fail to come about.
The GNU General Public License permits making a modified version and
letting the public access it on a server without ever releasing its
source code to the public.
The GNU Affero General Public License is designed specifically to
ensure that, in such cases, the modified source code becomes available
to the community. It requires the operator of a network server to
provide the source code of the modified version running there to the
users of that server. Therefore, public use of a modified version, on
a publicly accessible server, gives the public access to the source
code of the modified version.
An older license, called the Affero General Public License and
published by Affero, was designed to accomplish similar goals. This is
a different license, not a version of the Affero GPL, but Affero has
released a new version of the Affero GPL which permits relicensing under
this license.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU Affero General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Remote Network Interaction; Use with the GNU General Public License.
Notwithstanding any other provision of this License, if you modify the
Program, your modified version must prominently offer all users
interacting with it remotely through a computer network (if your version
supports such interaction) an opportunity to receive the Corresponding
Source of your version by providing access to the Corresponding Source
from a network server at no charge, through some standard or customary
means of facilitating copying of software. This Corresponding Source
shall include the Corresponding Source for any work covered by version 3
of the GNU General Public License that is incorporated pursuant to the
following paragraph.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the work with which it is combined will remain governed by version
3 of the GNU General Public License.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU Affero General Public License from time to time. Such new versions
will be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU Affero General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU Affero General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU Affero General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU Affero General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU Affero General Public License for more details.
You should have received a copy of the GNU Affero General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If your software can interact with users remotely through a computer
network, you should also make sure that it provides a way for users to
get its source. For example, if your program is a web application, its
interface could display a "Source" link that leads users to an archive
of the code. There are many ways you could offer source, and different
solutions will be better for different programs; see section 13 for the
specific requirements.
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU AGPL, see
<http://www.gnu.org/licenses/>.

View File

@@ -2,3 +2,7 @@
HamShield Arduino Library and Example Sketches 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. 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

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

@@ -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

@@ -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);
}

57
examples/DDS/DDS.ino Normal file
View File

@@ -0,0 +1,57 @@
#define DDS_REFCLK_DEFAULT 9600
#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);
radio.initialize();
radio.setRfPower(0);
radio.setFrequency(145060);
radio.setModeTransmit();
dds.start();
dds.playWait(600, 3000);
dds.on();
//dds.setAmplitude(31);
}
void loop() {
dds.setFrequency(2200);
delay(1000);
dds.setFrequency(1200);
delay(1000);
}
#ifdef DDS_USE_ONLY_TIMER2
ISR(TIMER2_OVF_vect) {
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

@@ -5,23 +5,34 @@ Test beacon will transmit and wait 30 seconds.
Beacon will check to see if the channel is clear before it will transmit. Beacon will check to see if the channel is clear before it will transmit.
*/ */
// Include the HamSheild and Wire (I2C) libraries // Include the HamSheild
#include <HamShield.h> #include <HamShield.h>
#include <Wire.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
// Create a new instance of our HamSheild class, called 'radio' // Create a new instance of our HamSheild class, called 'radio'
HamShield radio; HamShield radio;
// Run our start up things here // Run our start up things here
void setup() { 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);
// Set up the serial port at 9600 Baud // Set up the serial port at 9600 Baud
Serial.begin(9600); Serial.begin(9600);
// Send a quick serial string // Send a quick serial string
Serial.println("HamShield FM Beacon Example Sketch"); Serial.println("HamShield FM Beacon Example Sketch");
// Start the Wire (I2C) library
Wire.begin();
// Query the HamShield for status information // Query the HamShield for status information
Serial.print("Radio status: "); Serial.print("Radio status: ");
@@ -30,16 +41,16 @@ void setup() {
// Tell the HamShield to start up // Tell the HamShield to start up
radio.initialize(); radio.initialize();
radio.setRfPower(0);
// Configure the HamShield to transmit and recieve on 446.000MHz // Configure the HamShield to transmit and recieve on 446.000MHz
radio.frequency(446000); radio.frequency(145570);
Serial.println("Radio Configured."); Serial.println("Radio Configured.");
} }
void loop() { 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 // 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,-50)) { if (radio.waitForChannel(30000,2000,-5)) {
// If we get here, the channel is clear. Let's print the RSSI to the serial port as well. // 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.print("Signal is clear, RSSI: ");
Serial.println(radio.readRSSI()); Serial.println(radio.readRSSI());
@@ -49,14 +60,14 @@ void loop() {
radio.setModeTransmit(); radio.setModeTransmit();
// Send a message out in morse code // Send a message out in morse code
radio.morseOut("CALLSIGN LOCATOR ARDUINO HAMSHIELD"); radio.morseOut("KC7IBT ARDUINO HAMSHIELD");
// We're done sending the message, set the radio back into recieve mode. // We're done sending the message, set the radio back into recieve mode.
radio.setModeReceive(); radio.setModeReceive();
Serial.println("Done."); Serial.println("Done.");
// Wait 30 seconds before we send our beacon again. // Wait 30 seconds before we send our beacon again.
delay(30000); delay(1000);
} else { } else {
// If we get here, the channel is busy. Let's also print out the RSSI. // 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.print("The channel was busy. Waiting 10 seconds. RSSI: ");

View File

@@ -1,7 +1,10 @@
/* Fox Hunt */ /* Fox Hunt */
#include <HAMShield.h> #include <HamShield.h>
#include <Wire.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
// transmit for 1 minute, every 10 minutes // transmit for 1 minute, every 10 minutes
@@ -9,18 +12,28 @@
#define INTERVAL 10 #define INTERVAL 10
#define RANDOMCHANCE 3 #define RANDOMCHANCE 3
HAMShield radio; HamShield radio;
void setup() { void setup() {
Wire.begin(); // 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);
radio.initialize(); radio.initialize();
radio.setFrequency(145510); radio.frequency(145510);
radio.setModeReceive(); radio.setModeReceive();
} }
void loop() { void loop() {
waitMinute(INTERVAL + random(0,RANDOMCHANCE)); // wait before transmitting, randomly up to 3 minutes later waitMinute(INTERVAL + random(0,RANDOMCHANCE)); // wait before transmitting, randomly up to 3 minutes later
if(radio.waitForChannel(30000,2000)) { // wait for a clear channel, abort after 30 seconds, wait 2 seconds of dead air for breakers 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 radio.setModeTransmit(); // turn on transmit mode
tone(1000,11,TRANSMITLENGTH * 60 * 1000); // play a long solid tone tone(1000,11,TRANSMITLENGTH * 60 * 1000); // play a long solid tone
radio.morseOut("1ZZ9ZZ/B FOXHUNT"); // identify the fox hunt transmitter radio.morseOut("1ZZ9ZZ/B FOXHUNT"); // identify the fox hunt transmitter
@@ -34,4 +47,3 @@ void waitMinute(int period) {
delay(period * 60 * 1000); 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.");
}

View File

@@ -7,10 +7,13 @@ Simple gauges for the radio receiver.
*/ */
#include <HAMShield.h> #include <HamShield.h>
#include <Wire.h>
HAMShield radio; #define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
void clr() { void clr() {
/* Serial.write(27); /* Serial.write(27);
@@ -19,10 +22,21 @@ void clr() {
Serial.print("[H"); // cursor to home command Serial.print("[H"); // cursor to home command
} }
void setup() { 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); analogReference(DEFAULT);
Serial.begin(115200); Serial.begin(115200);
Wire.begin();
Serial.print("Radio status: "); Serial.print("Radio status: ");
int result = radio.testConnection(); int result = radio.testConnection();
Serial.println(result,DEC); Serial.println(result,DEC);

View File

@@ -1,17 +1,31 @@
/* Simple DTMF controlled HAM Radio Robot */ /* Simple DTMF controlled HAM Radio Robot */
#include <ArduinoRobot.h> // include the robot library #include <ArduinoRobot.h> // include the robot library
#include <HAMShield.h> #include <HamShield.h>
#include <Wire.h>
#include <SPI.h> #include <SPI.h>
HAMShield radio; #define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
void setup() { 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(); Robot.begin();
Wire.begin();
radio.initialize(); radio.initialize();
radio.setFrequency(145510); radio.frequency(145510);
} }
void loop() { void loop() {

View File

@@ -0,0 +1,132 @@
// Hamshield
#include <HamShield.h>
// create object for radio
HamShield radio;
#define LED_PIN 13
#define RSSI_REPORT_RATE_MS 5000
//TODO: move these into library
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
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(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);
// 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);
Serial.println("beginning radio setup");
// 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");
radio.dangerMode();
// set frequency
Serial.println("changing frequency");
radio.setSQOff();
freq = 446000;
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);
rssi_timeout = 0;
}
void loop() {
if (!digitalRead(SWITCH_PIN))
{
if (!currently_tx)
{
currently_tx = true;
// set to transmit
radio.setModeTransmit();
Serial.println("Tx");
//radio.setTxSourceMic();
//radio.setRfPower(1);
}
} else if (currently_tx) {
radio.setModeReceive();
currently_tx = false;
Serial.println("Rx");
}
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();
Serial.flush();
radio.frequency(freq);
Serial.print("set frequency: ");
Serial.println(freq);
}
}
if (!currently_tx && (millis() - rssi_timeout) > RSSI_REPORT_RATE_MS)
{
Serial.println(radio.readRSSI());
rssi_timeout = millis();
}
}

View File

@@ -6,12 +6,16 @@ Arduino audio overlay example
*/ */
#include <HAMShield.h>
#include <Wire.h> #include <HamShield.h>
#define DOT 100 #define DOT 100
HAMShield radio; #define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
const char *bascii = "ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789.,?'!/()&:;=+-_\"$@", const char *bascii = "ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789.,?'!/()&:;=+-_\"$@",
*bitu[] = { ".-","-...","-.-.","-..",".","..-.","--.","....","..",".---","-.-",".-..","--","-.","---",".--.","--.-",".-.","...","-","..-","...-",".--","-..-","-.--","--..","-----",".----","..---","...--","....-",".....","-....","--...","---..","----.",".-.-.-","--..--","..--..",".----.","-.-.--","-..-.","-.--.","-.--.-",".-...","---...","-.-.-.","-...-",".-.-.","-....-","..--.-",".-..-.","...-..-",".--.-." *bitu[] = { ".-","-...","-.-.","-..",".","..-.","--.","....","..",".---","-.-",".-..","--","-.","---",".--.","--.-",".-.","...","-","..-","...-",".--","-..-","-.--","--..","-----",".----","..---","...--","....-",".....","-....","--...","---..","----.",".-.-.-","--..--","..--..",".----.","-.-.--","-..-.","-.--.","-.--.-",".-...","---...","-.-.-.","-...-",".-.-.","-....-","..--.-",".-..-.","...-..-",".--.-."
@@ -21,15 +25,26 @@ const char *callsign = {"1ZZ9ZZ/B"} ;
char morsebuffer[8]; char morsebuffer[8];
void setup() { 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.begin(9600);
Serial.println("starting up.."); Serial.println("starting up..");
Wire.begin();
Serial.print("Radio status: "); Serial.print("Radio status: ");
int result = radio.testConnection(); int result = radio.testConnection();
Serial.println(result,DEC); Serial.println(result,DEC);
radio.initialize(); radio.initialize();
radio.setFrequency(446000); radio.frequency(446000);
radio.setVolume1(0xF); radio.setVolume1(0xF);
radio.setVolume2(0xF); radio.setVolume2(0xF);
radio.setModeReceive(); radio.setModeReceive();

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(;;) { }
}

47
examples/KISS/KISS.ino Normal file
View File

@@ -0,0 +1,47 @@
#include <HamShield.h>
#include <KISS.h>
HamShield radio;
DDS dds;
KISS kiss(&Serial, &radio, &dds);
//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(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);
while (digitalRead(SWITCH_PIN));
// let the AU ot of reset
digitalWrite(RESET_PIN, HIGH);
radio.initialize();
radio.setSQOff();
radio.setFrequency(144390);
//I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x44, 0x05FF);
dds.start();
radio.afsk.start(&dds);
}
void loop() {
kiss.loop();
}
ISR(ADC_vect) {
kiss.isr();
}

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
};

View File

@@ -6,13 +6,16 @@ A bit robotic and weird
*/ */
#include <HAMShield.h> #include <HamShield.h>
#include <Wire.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
#define RATE 500 #define RATE 500
#define SIZE 1500 #define SIZE 1500
HAMShield radio; HamShield radio;
char sound[SIZE]; char sound[SIZE];
unsigned int sample1; unsigned int sample1;
@@ -21,7 +24,17 @@ int16_t rssi;
byte mode = 8; byte mode = 8;
void setup() { void setup() {
Wire.begin(); // 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(); // int result = radio.testConnection();
radio.initialize(); radio.initialize();
radio.setFrequency(446000); radio.setFrequency(446000);

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

@@ -4,27 +4,40 @@ Sends an SSTV test pattern
*/ */
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
#define DOT 100 #define DOT 100
#define CALLSIGN "1ZZ9ZZ/B" #define CALLSIGN "1ZZ9ZZ/B"
/* Standard libraries and variable init */ /* Standard libraries and variable init */
#include <HAMShield.h> #include <HamShield.h>
#include <Wire.h>
HAMShield radio; HamShield radio;
int16_t rssi; int16_t rssi;
/* get our radio ready */ /* get our radio ready */
void setup() { void setup() {
Wire.begin(); // 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.begin(9600);
Serial.print("Radio status: "); Serial.print("Radio status: ");
int result = radio.testConnection(); int result = radio.testConnection();
Serial.println(result); Serial.println(result);
radio.initialize(); radio.initialize();
radio.setFrequency(446000); radio.frequency(446000);
radio.setModeReceive(); radio.setModeReceive();
} }

View File

@@ -0,0 +1,440 @@
// So the precalculated values will get stored
#define DDS_REFCLK_DEFAULT (34965/2)
#include <HamShield.h>
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
DDS dds;
// Defined at the end of the sketch
extern const uint16_t image[256*20] PROGMEM;
#define F_1200 0
#define F_1500 1
#define F_2400 2
ddsAccumulator_t freqTable[3];
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);
// Query the HamShield for status information
Serial.print("Radio status: ");
int result = 0;
result = radio.testConnection();
Serial.println(result,DEC);
// Tell the HamShield to start up
radio.initialize();
radio.setRfPower(0);
radio.frequency(145500);
// put your setup code here, to run once:
//dds.setReferenceClock(34965/4);
dds.start();
freqTable[F_1200] = dds.calcFrequency(1200);
freqTable[F_1500] = dds.calcFrequency(1500);
freqTable[F_2400] = dds.calcFrequency(2400);
dds.setFrequency(1000);
dds.on();
Serial.println("DDS on");
delay(1000);
dds.off();
delay(2000);
Serial.println("Next");
}
uint8_t code = MARTIN1;
bool parityCalc(int code) {
unsigned int v; // word value to compute the parity of
bool parity = false; // parity will be the parity of v
while (code)
{
parity = !parity;
code = code & (code - 1);
}
return parity;
}
volatile bool registered = false;
volatile bool scanning = false;
volatile bool done = false;
volatile uint16_t nextBlock = 0;
volatile uint8_t currentScanline = 0;
volatile uint16_t scanline[2][20];
// Format is 3 'images', one each for green, blue and red
// But we don't have room, so it's monochrome
// 256 rows each
// 10 sets of 32 bits encoding on/off for the colour
//const unsigned long image[256][10] PROGMEM = {
//};
void loadScanline(uint8_t s, int y) {
for(int i = 0; i < 20; i++) {
scanline[s][i] = pgm_read_word_near(image + y*20 + i);
}
}
#define DON() PORTD |= _BV(2);
#define DOFF() PORTD &= ~_BV(2);
void loop() {
// Load the first scanline
loadScanline(0, 0);
radio.setModeTransmit();
delay(500);
// VIS
dds.playWait(1900,300);
dds.playWait(1200,10);
dds.playWait(1900,300);
dds.playWait(1200,30);
for(int x = 0; x < 7; x++) {
if(bitRead(code,x)) { dds.playWait(1100,30); } else { dds.playWait(1300,30); }
}
if(parityCalc(code)) { dds.playWait(1300,30); } else { dds.playWait(1100,30); }
dds.playWait(1200,30);
dds.on();
for(int y = 1; y < 256; y++){
DON();
dds.setPrecalcFrequency(freqTable[F_1200]);
// Subtract for the timer ticks
delayMicroseconds(3562); // sync pulse (4862 uS)
DOFF();
DON();
dds.setPrecalcFrequency(freqTable[F_1500]);
// Subtract for the timer ticks
delayMicroseconds(442); // sync porch (572 uS)
DOFF();
scanning = true;
for(uint8_t c = 0; c<3; c++) {
scanning = true;
while(!registered);
registered = false;
loadScanline((++currentScanline) & 1, y);
while(!done);
dds.setPrecalcFrequency(freqTable[F_1500]);
done = false;
scanning = false;
DON();
delayMicroseconds(442); // color separator pulse (572 uS)
DOFF();
}
}
dds.off();
radio.setModeReceive();
delay(10000);
return;
}
// The DDS is running faster than the pixel clock, so we
// only update the pixel frequency every few ticks.
ISR(ADC_vect) {
static uint8_t tcnt = 0;
static uint8_t shifts = 0;
static uint8_t shiftingLine = 0;
static uint8_t linePos = 0;
static uint16_t pixelBlock;
TIFR1 |= _BV(ICF1);
dds.clockTick();
if(scanning) {
if(++tcnt == 8) {
tcnt = 0;
if(linePos == 21) {
done = true;
linePos = 0;
}
if(linePos == 0) {
shifts = 0;
shiftingLine = currentScanline&1;
registered = true;
}
if(shifts == 0) {
pixelBlock = scanline[shiftingLine][linePos++];
}
if(pixelBlock & 0x8000) {
dds.setPrecalcFrequency(freqTable[F_2400]);
} else {
dds.setPrecalcFrequency(freqTable[F_1500]);
}
if(++shifts == 16) {
shifts = 0;
}
pixelBlock <<= 1;
}
}
}
// Image is 256 lines * 320 pixels per line, packed to 16 bits at a time
const uint16_t image[256*20] PROGMEM = {
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 1
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 2
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 3
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 4
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 5
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 6
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 7
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 8
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 9
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 10
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 11
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 12
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 13
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 14
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 15
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 16
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 17
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 18
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 19
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 20
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 21
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 22
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 23
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 24
0xFFFF, 0xE0FF, 0x07FF, 0xBFCF, 0xFFFF, 0xFFC1, 0xF3FE, 0x7FF9, 0xFF3F, 0xFC1F, 0xE0FF, 0xF7F9, 0xFFFF, 0xFFF8, 0x3E7F, 0xCFFF, 0x3FE7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 25
0xFFFF, 0x807C, 0x03FF, 0x3FCF, 0xFFFF, 0xFF80, 0x73FE, 0x7FF9, 0xFF3F, 0xF00F, 0x807F, 0xE7F9, 0xFFFF, 0xFFF0, 0x0E7F, 0xCFFF, 0x3FE7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 26
0xFFFF, 0x1F38, 0xF9FF, 0x3FCF, 0xFFFF, 0xFF1E, 0x33FF, 0xFFF9, 0xFF3F, 0xE3E7, 0x1F3F, 0xE7F9, 0xFFFF, 0xFFE3, 0xC67F, 0xFFFF, 0x3FE7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 27
0xFFFF, 0x3F19, 0xFCFF, 0x3FCF, 0xFFFF, 0xFF3F, 0x33FF, 0xFFF9, 0xFF3F, 0xE7E3, 0x3F9F, 0xE7F9, 0xFFFF, 0xFFE7, 0xE67F, 0xFFFF, 0x3FE7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 28
0xFFFE, 0x7FF3, 0xFCFF, 0x3FCF, 0x0723, 0x8F3F, 0xF21E, 0x7879, 0xE13F, 0xCFFE, 0x7F9F, 0xE7F9, 0xE0E4, 0x71E7, 0xFE43, 0xCF0F, 0x3C27, 0xFFFF, 0xFFFF, 0xFFFF, // Line 29
0xFFFE, 0x7FF3, 0xFCFF, 0x3FCE, 0x0300, 0x071F, 0xF00E, 0x7019, 0xC03F, 0xCFFE, 0x7F9F, 0xE7F9, 0xC060, 0x00E3, 0xFE01, 0xCE03, 0x3807, 0xFFFF, 0xFFFF, 0xFFFF, // Line 30
0xFFFE, 0x7FF3, 0xFE7F, 0x000C, 0xF31C, 0x7381, 0xF1E6, 0x6799, 0x9E3F, 0xCFFE, 0x7FCF, 0xE001, 0x9E63, 0x8E70, 0x3E3C, 0xCCF3, 0x33C7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 31
0xFFFE, 0x7FF3, 0xFC7F, 0x000F, 0x833C, 0xF3F0, 0x73E6, 0x67C9, 0x9F3F, 0xCFFE, 0x7F8F, 0xE001, 0xF067, 0x9E7E, 0x0E7C, 0xCCF9, 0x33E7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 32
0xFFFE, 0x7FF3, 0xFCFF, 0x3FCE, 0x033C, 0xF3FF, 0x33E6, 0x6009, 0x9F3F, 0xCFFE, 0x7F9F, 0xE7F9, 0xC067, 0x9E7F, 0xE67C, 0xCC01, 0x33E7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 33
0xFFFE, 0x7FB3, 0xFCFF, 0x3FCC, 0xF33C, 0xF3FF, 0x33E6, 0x67F9, 0x9F3F, 0xCFF6, 0x7F9F, 0xE7F9, 0x9E67, 0x9E7F, 0xE67C, 0xCCFF, 0x33E7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 34
0xFFFF, 0x3F19, 0xE0FF, 0x3FCC, 0xF33C, 0xF33F, 0x33E6, 0x67F9, 0x9F3F, 0xE7E3, 0x3C1F, 0xE7F9, 0x9E67, 0x9E67, 0xE67C, 0xCCFF, 0x33E7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 35
0xFFFF, 0x1F38, 0xF1FF, 0x3FCC, 0xE33C, 0xF31F, 0x33E6, 0x6789, 0x9E3F, 0xE3E7, 0x1E3F, 0xE7F9, 0x9C67, 0x9E63, 0xE67C, 0xCCF1, 0x33C7, 0xFFFF, 0xFFFF, 0xFFFF, // Line 36
0xFFFF, 0x807C, 0x01FF, 0x3FCC, 0x033C, 0xF380, 0x73E6, 0x7019, 0xC03F, 0xF00F, 0x803F, 0xE7F9, 0x8067, 0x9E70, 0x0E7C, 0xCE03, 0x3807, 0xFFFF, 0xFFFF, 0xFFFF, // Line 37
0xFFFF, 0xE0FF, 0x04FF, 0xBFCE, 0x1B3C, 0xF3C0, 0xF3E6, 0x7839, 0xE13F, 0xFC1F, 0xE09F, 0xF7F9, 0xC367, 0x9E78, 0x1E7C, 0xCF07, 0x3C27, 0xFFFF, 0xFFFF, 0xFFFF, // Line 38
0xFFFF, 0xFFFF, 0xFEFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFDF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 39
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 40
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 41
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 42
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 43
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 44
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 45
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 46
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 47
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 48
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 49
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 50
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 51
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 52
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 53
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 54
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 55
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x1FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 56
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 57
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF80, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 58
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFE00, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 59
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFC3, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 60
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x3FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 61
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x0FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 62
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 63
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0000, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 64
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0000, 0x00FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 65
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0000, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 66
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0000, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 67
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF8, 0x0000, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 68
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF8, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 69
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF8, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 70
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 71
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 72
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 73
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 74
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 75
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 76
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 77
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 78
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 79
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 80
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 81
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0000, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 82
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0000, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x07FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 83
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF8, 0x0000, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 84
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0000, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 85
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0000, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 86
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x07FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 87
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 88
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 89
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 90
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 91
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 92
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 93
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 94
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 95
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 96
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 97
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 98
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 99
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 100
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 101
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 102
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 103
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 104
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 105
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 106
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 107
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 108
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 109
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x87FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 110
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 111
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 112
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 113
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 114
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 115
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 116
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x87FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 117
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 118
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 119
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 120
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 121
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 122
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 123
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 124
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 125
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 126
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 127
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 128
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 129
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF9FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 130
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE07F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 131
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC03F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 132
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x801F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 133
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 134
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 135
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 136
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 137
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 138
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF83, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 139
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFE01, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 140
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 141
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 142
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 143
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 144
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 145
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 146
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x3FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 147
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x1FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 148
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x07FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 149
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 150
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x00FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 151
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 152
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 153
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFE00, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFC0, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 154
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF00, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF00, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 155
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF80, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFE00, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 156
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFC0, 0x0000, 0x3FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 157
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 158
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 159
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0000, 0x00FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x00FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 160
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0000, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xC000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 161
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0000, 0x07FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 162
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0000, 0x1FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 163
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF0, 0x0000, 0x3FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 164
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x0000, 0x3FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFC0, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 165
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFE00, 0x0000, 0x0FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF00, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 166
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF80, 0x0000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 167
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x00FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 168
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF8, 0x0000, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 169
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 170
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0003, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF80, 0x0000, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 171
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x0000, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 172
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFC00, 0x0000, 0x3FFF, 0xFFFF, 0xFFFF, 0xF000, 0x0000, 0x01FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 173
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF00, 0x0000, 0x07FF, 0xFFFF, 0xFFFF, 0xC000, 0x0000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 174
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF80, 0x0000, 0x001F, 0xFFFF, 0xFFF8, 0x0000, 0x0000, 0x0FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 175
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0000, 0x1FFF, 0xA000, 0x0000, 0x0000, 0x7FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 176
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFF8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0001, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 177
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x000F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 178
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x8000, 0x0000, 0x0000, 0x0000, 0x0000, 0x003F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 179
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xE000, 0x0000, 0x0000, 0x0000, 0x0000, 0x00FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 180
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF800, 0x0000, 0x0000, 0x0000, 0x0000, 0x0FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 181
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFE00, 0x0000, 0x0000, 0x0000, 0x0000, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 182
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFF80, 0x0000, 0x0000, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 183
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFE0, 0x0000, 0x0000, 0x0000, 0x001F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 184
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0x0000, 0x0000, 0x0000, 0x007F, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 185
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x0000, 0x0000, 0x0000, 0x03FF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 186
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF000, 0x0000, 0x0000, 0x1FFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 187
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFC0, 0x0000, 0x0007, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 188
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 189
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 190
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 191
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 192
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 193
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 194
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 195
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 196
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 197
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 198
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 199
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 200
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 201
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 202
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 203
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 204
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 205
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 206
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 207
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 208
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 209
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 210
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 211
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 212
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 213
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 214
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 215
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 216
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 217
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 218
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 219
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 220
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 221
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 222
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 223
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 224
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 225
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 226
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 227
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 228
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 229
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF9FF, 0xFFBF, 0xEE00, 0xF87F, 0x07EF, 0xFC03, 0xFFFF, 0xFFFF, // Line 230
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF9FF, 0xFF9F, 0xCC00, 0xF01E, 0x01CF, 0xF801, 0xFFFF, 0xFFFF, // Line 231
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF9FF, 0xFF9F, 0xCCFF, 0xE79C, 0x78CF, 0xF9F8, 0xFFFF, 0xFFFF, // Line 232
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xF9FF, 0xFF8F, 0x8CFF, 0xEFDC, 0xFCCF, 0xF9FC, 0xFFFF, 0xFFFF, // Line 233
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x09E1, 0xFFCF, 0x9CFF, 0xCFFC, 0xFFCF, 0xF9FC, 0xFFFF, 0xFFFF, // Line 234
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x01C0, 0x7FCF, 0x9CFF, 0xC83C, 0x7FCF, 0xF9F8, 0xFFFF, 0xFFFF, // Line 235
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0xF19E, 0x7FE7, 0x3C01, 0xC01E, 0x07CF, 0xF801, 0xFFFF, 0xFFFF, // Line 236
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0xF99F, 0x3FE7, 0x3C01, 0xC78F, 0xC1CF, 0xF803, 0xFFFF, 0xFFFF, // Line 237
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0xF980, 0x3FE7, 0x3CFF, 0xCFCF, 0xFCCF, 0xF9FF, 0xFFFF, 0xFFFF, // Line 238
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0xF99F, 0xFFF2, 0x7CFF, 0xCFCF, 0xFCCF, 0xF9FF, 0xFFFF, 0xFFFF, // Line 239
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0xF99F, 0xFFF2, 0x7CFF, 0xCFCC, 0xFCCF, 0xF9FF, 0xFFFF, 0xFFFF, // Line 240
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFC, 0xF19E, 0x3FF8, 0xFCFF, 0xE79C, 0x7CCF, 0xF9FF, 0xFFFF, 0xFFFF, // Line 241
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFE, 0x01C0, 0x7FF8, 0xFC00, 0xF01E, 0x01E0, 0x09FF, 0xFFFF, 0xFFFF, // Line 242
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0x09E0, 0xFFF8, 0xFE00, 0xF87F, 0x03E0, 0x0DFF, 0xFFFF, 0xFFFF, // Line 243
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 244
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 245
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 246
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 247
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 248
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 249
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 250
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 251
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 252
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 253
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 254
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 255
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, // Line 256
};

40
examples/SerialTransceiver/SerialTransceiver.ino Executable file → Normal file
View File

@@ -1,6 +1,6 @@
/* /*
SerialTransceiver is TTL Serial port "glue" to allow desktop or laptop control of the HAMShield SerialTransceiver is TTL Serial port "glue" to allow desktop or laptop control of the HamShield
Commands: Commands:
@@ -17,6 +17,7 @@ Frequency F<freq>; Set the receive frequency in KHz, if offset is disabl
CDCSS In G<code>; <code> must be a valid CDCSS code 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 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 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 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 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 Squelch S<level>; Set the squelch level No
@@ -45,8 +46,11 @@ Debug Msg @<text>; 32 character debug message
*/ */
#include "Wire.h" #include "HamShield.h"
#include "HAMShield.h"
#define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
int state; int state;
int txcount = 0; int txcount = 0;
@@ -62,14 +66,25 @@ int cdcssin = 0;
int cdcssout = 0; int cdcssout = 0;
HAMShield radio; HamShield radio;
void setup() { 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.begin(115200);
Serial.print(";;;;;;;;;;;;;;;;;;;;;;;;;;"); Serial.print(";;;;;;;;;;;;;;;;;;;;;;;;;;");
Wire.begin();
int result = radio.testConnection(); int result = radio.testConnection();
Serial.print("*"); Serial.print("*");
Serial.print(result,DEC); Serial.print(result,DEC);
@@ -81,7 +96,7 @@ void setup() {
radio.setVolume2(0xF); radio.setVolume2(0xF);
radio.setModeReceive(); radio.setModeReceive();
radio.setTxSourceMic(); radio.setTxSourceMic();
radio.setRfPower(9); radio.setRfPower(0);
radio.setSQLoThresh(80); radio.setSQLoThresh(80);
radio.setSQOn(); radio.setSQOn();
} }
@@ -103,8 +118,7 @@ void loop() {
case 32: // space - transmit case 32: // space - transmit
if(repeater == 1) { radio.frequency(tx); } if(repeater == 1) { radio.frequency(tx); }
radio.setRX(0); radio.setModeTransmit();
radio.setTX(1);
state = 10; state = 10;
Serial.print("#TX,ON;"); Serial.print("#TX,ON;");
timer = millis(); timer = millis();
@@ -136,6 +150,14 @@ void loop() {
freq = atol(cmdbuff); freq = atol(cmdbuff);
if(radio.frequency(freq) == true) { Serial.print("@"); Serial.print(freq,DEC); Serial.print(";!;"); } else { Serial.print("X1;"); } if(radio.frequency(freq) == true) { Serial.print("@"); Serial.print(freq,DEC); Serial.print(";!;"); } else { Serial.print("X1;"); }
break; break;
case 'M':
getValue();
radio.setModeTransmit();
delay(300);
radio.morseOut(cmdbuff);
state = 10;
break;
case 80: // P - power level case 80: // P - power level
getValue(); getValue();
@@ -172,7 +194,7 @@ void loop() {
} }
if(state == 10) { if(state == 10) {
if(millis() > (timer + 500)) { Serial.print("#TX,OFF;");radio.setRX(1); radio.setTX(0); if(repeater == 1) { radio.frequency(freq); } state = 0; txcount = 0; } if(millis() > (timer + 500)) { Serial.print("#TX,OFF;");radio.setModeReceive(); if(repeater == 1) { radio.frequency(freq); } state = 0; txcount = 0; }
} }
} }

View File

@@ -10,11 +10,14 @@ Plays back the current signal strength level and morses out it's call sign at th
/* Standard libraries and variable init */ /* Standard libraries and variable init */
#include <HAMShield.h> #include <HamShield.h>
#include <Wire.h>
#include <PCM.h> #include <PCM.h>
HAMShield radio; #define PWM_PIN 3
#define RESET_PIN A3
#define SWITCH_PIN 2
HamShield radio;
int16_t rssi; int16_t rssi;
int peak = -150; int peak = -150;
char sig[8]; char sig[8];
@@ -73,14 +76,24 @@ const unsigned char dbm[] PROGMEM = {
/* get our radio ready */ /* get our radio ready */
void setup() { void setup() {
Wire.begin(); // 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.begin(9600);
Serial.print("Radio status: "); Serial.print("Radio status: ");
int result = radio.testConnection(); int result = radio.testConnection();
Serial.println(result); Serial.println(result);
radio.initialize(); radio.initialize();
radio.setFrequency(446000); radio.frequency(446000);
radio.setVolume1(0xF); radio.setVolume1(0xF);
radio.setVolume2(0xF); radio.setVolume2(0xF);
radio.setModeReceive(); radio.setModeReceive();
@@ -104,7 +117,7 @@ void loop() {
if(rssi < -120) { if(rssi < -120) {
Serial.println("Transmit On"); Serial.println("Transmit On");
radio.setTX(1); radio.setModeTransmit();
delay(250); delay(250);
tone(11,1000,500); tone(11,1000,500);
delay(1000); delay(1000);
@@ -131,9 +144,8 @@ void loop() {
delay(1000); delay(1000);
Serial.println("done!"); Serial.println("done!");
radio.morseOut(CALLSIGN); radio.morseOut(CALLSIGN);
radio.setTX(0);
Serial.println("Transmit off");
radio.setModeReceive(); radio.setModeReceive();
Serial.println("Transmit off");
delay(1000); delay(1000);
} }
} }