Compare commits
1 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
91aa8506cf |
738
AFSK.cpp
Normal file
738
AFSK.cpp
Normal 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
301
AFSK.h
Normal 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
175
DDS.cpp
Normal 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
228
DDS.h
Normal 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_ */
|
||||
@@ -119,32 +119,18 @@ volatile long bouncer = 0;
|
||||
* @see A1846S_DEFAULT_ADDRESS
|
||||
*/
|
||||
HamShield::HamShield() {
|
||||
devAddr = A1; // devAddr is the chip select pin used by the HamShield
|
||||
devAddr = A1846S_DEV_ADDR_SENLOW;
|
||||
sHamShield = this;
|
||||
|
||||
pinMode(devAddr, OUTPUT);
|
||||
digitalWrite(devAddr, HIGH);
|
||||
pinMode(CLK, OUTPUT);
|
||||
digitalWrite(CLK, HIGH);
|
||||
pinMode(DAT, OUTPUT);
|
||||
digitalWrite(DAT, HIGH);
|
||||
}
|
||||
|
||||
/** Specific address constructor.
|
||||
* @param chip select pin for HamShield
|
||||
* @param address I2C address
|
||||
* @see A1846S_DEFAULT_ADDRESS
|
||||
* @see A1846S_ADDRESS_AD0_LOW
|
||||
* @see A1846S_ADDRESS_AD0_HIGH
|
||||
*/
|
||||
HamShield::HamShield(uint8_t cs_pin) {
|
||||
devAddr = cs_pin;
|
||||
|
||||
pinMode(devAddr, OUTPUT);
|
||||
digitalWrite(devAddr, HIGH);
|
||||
pinMode(CLK, OUTPUT);
|
||||
digitalWrite(CLK, HIGH);
|
||||
pinMode(DAT, OUTPUT);
|
||||
digitalWrite(DAT, HIGH);
|
||||
HamShield::HamShield(uint8_t address) {
|
||||
devAddr = address;
|
||||
}
|
||||
|
||||
/** Power on and prepare for general usage.
|
||||
@@ -164,130 +150,129 @@ void HamShield::initialize() {
|
||||
|
||||
// set up GPIO voltage (want 3.3V)
|
||||
tx_data = 0x03AC; // default is 0x32C
|
||||
HSwriteWord(devAddr, 0x09, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x09, tx_data);
|
||||
|
||||
tx_data = 0x47E0; //0x43A0; // 0x7C20; //
|
||||
HSwriteWord(devAddr, 0x0A, tx_data); // pga gain [10:6]
|
||||
I2Cdev::writeWord(devAddr, 0x0A, tx_data); // pga gain [10:6]
|
||||
tx_data = 0xA100;
|
||||
HSwriteWord(devAddr, 0x13, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x13, tx_data);
|
||||
tx_data = 0x5001;
|
||||
HSwriteWord(devAddr, 0x1F, tx_data); // GPIO7->VOX, GPIO0->CTC/DCS
|
||||
I2Cdev::writeWord(devAddr, 0x1F, tx_data); // GPIO7->VOX, GPIO0->CTC/DCS
|
||||
|
||||
|
||||
tx_data = 0x0031;
|
||||
HSwriteWord(devAddr, 0x31, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x31, tx_data);
|
||||
tx_data = 0x0AF2; //
|
||||
HSwriteWord(devAddr, 0x33, tx_data); // agc number
|
||||
I2Cdev::writeWord(devAddr, 0x33, tx_data); // agc number
|
||||
|
||||
// AGC table
|
||||
tx_data = 0x0001;
|
||||
HSwriteWord(devAddr, 0x7F, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x7F, tx_data);
|
||||
tx_data = 0x000C;
|
||||
HSwriteWord(devAddr, 0x05, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x05, tx_data);
|
||||
tx_data = 0x020C;
|
||||
HSwriteWord(devAddr, 0x06, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x06, tx_data);
|
||||
tx_data = 0x030C;
|
||||
HSwriteWord(devAddr, 0x07, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x07, tx_data);
|
||||
tx_data = 0x0324;
|
||||
HSwriteWord(devAddr, 0x08, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x08, tx_data);
|
||||
tx_data = 0x1344;
|
||||
HSwriteWord(devAddr, 0x09, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x09, tx_data);
|
||||
tx_data = 0x3F44;
|
||||
HSwriteWord(devAddr, 0x0A, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x0A, tx_data);
|
||||
tx_data = 0x3F44;
|
||||
HSwriteWord(devAddr, 0x0B, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x0B, tx_data);
|
||||
tx_data = 0x3F44;
|
||||
HSwriteWord(devAddr, 0x0C, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x0C, tx_data);
|
||||
tx_data = 0x3F44;
|
||||
HSwriteWord(devAddr, 0x0D, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x0D, tx_data);
|
||||
tx_data = 0x3F44;
|
||||
HSwriteWord(devAddr, 0x0E, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x0E, tx_data);
|
||||
tx_data = 0x3F44;
|
||||
HSwriteWord(devAddr, 0x0F, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x0F, tx_data);
|
||||
tx_data = 0xE0ED;
|
||||
HSwriteWord(devAddr, 0x12, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x12, tx_data);
|
||||
tx_data = 0xF2FE;
|
||||
HSwriteWord(devAddr, 0x13, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x13, tx_data);
|
||||
tx_data = 0x0A16;
|
||||
HSwriteWord(devAddr, 0x14, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x14, tx_data);
|
||||
tx_data = 0x2424;
|
||||
HSwriteWord(devAddr, 0x15, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x15, tx_data);
|
||||
tx_data = 0x2424;
|
||||
HSwriteWord(devAddr, 0x16, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x16, tx_data);
|
||||
tx_data = 0x2424;
|
||||
HSwriteWord(devAddr, 0x17, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x17, tx_data);
|
||||
tx_data = 0x0000;
|
||||
HSwriteWord(devAddr, 0x7F, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x7F, tx_data);
|
||||
// end AGC table
|
||||
|
||||
tx_data = 0x067F; //0x0601; //0x470F;
|
||||
HSwriteWord(devAddr, 0x41, tx_data); // voice gain tx [6:0]
|
||||
I2Cdev::writeWord(devAddr, 0x41, tx_data); // voice gain tx [6:0]
|
||||
tx_data = 0x02FF; // using 0x04FF to avoid tx voice delay
|
||||
HSwriteWord(devAddr, 0x44, tx_data); // tx gain [11:8]
|
||||
I2Cdev::writeWord(devAddr, 0x44, tx_data); // tx gain [11:8]
|
||||
tx_data = 0x7F2F;
|
||||
HSwriteWord(devAddr, 0x47, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x47, tx_data);
|
||||
tx_data = 0x2C62;
|
||||
HSwriteWord(devAddr, 0x4F, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x4F, tx_data);
|
||||
tx_data = 0x0094;
|
||||
HSwriteWord(devAddr, 0x53, tx_data); // compressor update time (bits 6:0, 5.12ms per unit)
|
||||
I2Cdev::writeWord(devAddr, 0x53, tx_data); // compressor update time (bits 6:0, 5.12ms per unit)
|
||||
tx_data = 0x2A18;
|
||||
HSwriteWord(devAddr, 0x54, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x54, tx_data);
|
||||
tx_data = 0x0081;
|
||||
HSwriteWord(devAddr, 0x55, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x55, tx_data);
|
||||
tx_data = 0x0B22;
|
||||
HSwriteWord(devAddr, 0x56, tx_data); // sq detect time
|
||||
I2Cdev::writeWord(devAddr, 0x56, tx_data); // sq detect time
|
||||
tx_data = 0x1C00;
|
||||
HSwriteWord(devAddr, 0x57, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x57, tx_data);
|
||||
tx_data = 0x800D;
|
||||
HSwriteWord(devAddr, 0x58, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x58, tx_data);
|
||||
tx_data = 0x0EDD;
|
||||
HSwriteWord(devAddr, 0x5A, tx_data); // sq and noise detect times
|
||||
I2Cdev::writeWord(devAddr, 0x5A, tx_data); // sq and noise detect times
|
||||
tx_data = 0x3FFF;
|
||||
HSwriteWord(devAddr, 0x63, tx_data); // pre-emphasis bypass
|
||||
I2Cdev::writeWord(devAddr, 0x63, tx_data); // pre-emphasis bypass
|
||||
|
||||
// calibration
|
||||
tx_data = 0x00A4;
|
||||
HSwriteWord(devAddr, 0x30, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x30, tx_data);
|
||||
delay(100);
|
||||
tx_data = 0x00A6;
|
||||
HSwriteWord(devAddr, 0x30, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x30, tx_data);
|
||||
delay(100);
|
||||
tx_data = 0x0006;
|
||||
HSwriteWord(devAddr, 0x30, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x30, tx_data);
|
||||
delay(100);
|
||||
|
||||
|
||||
// setup for 12.5kHz channel width
|
||||
tx_data = 0x3D37;
|
||||
HSwriteWord(devAddr, 0x11, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x11, tx_data);
|
||||
tx_data = 0x0100;
|
||||
HSwriteWord(devAddr, 0x12, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x12, tx_data);
|
||||
tx_data = 0x1100;
|
||||
HSwriteWord(devAddr, 0x15, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x15, tx_data);
|
||||
tx_data = 0x4495;
|
||||
HSwriteWord(devAddr, 0x32, tx_data); // agc target power [11:6]
|
||||
I2Cdev::writeWord(devAddr, 0x32, tx_data); // agc target power [11:6]
|
||||
tx_data = 0x2B8E;
|
||||
HSwriteWord(devAddr, 0x34, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x34, tx_data);
|
||||
tx_data = 0x40C3;
|
||||
HSwriteWord(devAddr, 0x3A, tx_data); // modu_det_sel sq setting
|
||||
I2Cdev::writeWord(devAddr, 0x3A, tx_data); // modu_det_sel sq setting
|
||||
tx_data = 0x0407;
|
||||
HSwriteWord(devAddr, 0x3C, tx_data); // pk_det_th sq setting [8:7]
|
||||
I2Cdev::writeWord(devAddr, 0x3C, tx_data); // pk_det_th sq setting [8:7]
|
||||
tx_data = 0x28D0;
|
||||
HSwriteWord(devAddr, 0x3F, tx_data); // rssi3_th sq setting
|
||||
I2Cdev::writeWord(devAddr, 0x3F, tx_data); // rssi3_th sq setting
|
||||
tx_data = 0x203E;
|
||||
HSwriteWord(devAddr, 0x48, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x48, tx_data);
|
||||
tx_data = 0x1BB7;
|
||||
HSwriteWord(devAddr, 0x60, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x60, tx_data);
|
||||
tx_data = 0x0A10; // use 0x1425 if there's an LNA
|
||||
HSwriteWord(devAddr, 0x62, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x62, tx_data);
|
||||
tx_data = 0x2494;
|
||||
HSwriteWord(devAddr, 0x65, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x65, tx_data);
|
||||
tx_data = 0xEB2E;
|
||||
HSwriteWord(devAddr, 0x66, tx_data);
|
||||
I2Cdev::writeWord(devAddr, 0x66, tx_data);
|
||||
|
||||
delay(100);
|
||||
|
||||
/*
|
||||
// setup default values
|
||||
frequency(446000);
|
||||
//setVolume1(0xF);
|
||||
@@ -297,7 +282,6 @@ void HamShield::initialize() {
|
||||
setRfPower(0);
|
||||
setSQLoThresh(80);
|
||||
setSQOn();
|
||||
*/
|
||||
}
|
||||
|
||||
/** Verify the I2C connection.
|
||||
@@ -305,7 +289,7 @@ void HamShield::initialize() {
|
||||
* @return True if connection is valid, false otherwise
|
||||
*/
|
||||
bool HamShield::testConnection() {
|
||||
HSreadWord(devAddr, 0x00, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, 0x00, radio_i2c_buf);
|
||||
return radio_i2c_buf[0] == 0x1846;
|
||||
}
|
||||
|
||||
@@ -332,16 +316,16 @@ bool HamShield::testConnection() {
|
||||
*/
|
||||
|
||||
uint16_t HamShield::readCtlReg() {
|
||||
HSreadWord(devAddr, A1846S_CTL_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_CTL_REG, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
void HamShield::softReset() {
|
||||
uint16_t tx_data = 0x1;
|
||||
HSwriteWord(devAddr, A1846S_CTL_REG, tx_data);
|
||||
I2Cdev::writeWord(devAddr, A1846S_CTL_REG, tx_data);
|
||||
delay(100); // Note: see A1846S setup info for timing guidelines
|
||||
tx_data = 0x4;
|
||||
HSwriteWord(devAddr, A1846S_CTL_REG, tx_data);
|
||||
I2Cdev::writeWord(devAddr, A1846S_CTL_REG, tx_data);
|
||||
}
|
||||
|
||||
|
||||
@@ -350,7 +334,7 @@ void HamShield::setFrequency(uint32_t freq_khz) {
|
||||
uint32_t freq_raw = freq_khz << 4; // shift by 4 to multiply by 16 (was shift by 3 in old 1846 chip)
|
||||
|
||||
// turn off tx/rx
|
||||
HSwriteBitsW(devAddr, A1846S_CTL_REG, 6, 2, 0);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_CTL_REG, 6, 2, 0);
|
||||
|
||||
// if we're using a 12MHz crystal and the frequency is
|
||||
// 136.5M,409.5M and 455M, then we have to do special stuff
|
||||
@@ -359,19 +343,19 @@ void HamShield::setFrequency(uint32_t freq_khz) {
|
||||
radio_frequency == 455000) {
|
||||
|
||||
// set up AU1846 for funky freq
|
||||
HSwriteWord(devAddr, 0x05, 0x86D3);
|
||||
I2Cdev::writeWord(devAddr, 0x05, 0x86D3);
|
||||
|
||||
} else {
|
||||
// set up AU1846 for normal freq
|
||||
HSwriteWord(devAddr, 0x05, 0x8763);
|
||||
I2Cdev::writeWord(devAddr, 0x05, 0x8763);
|
||||
}
|
||||
|
||||
// send top 16 bits to A1846S_FREQ_HI_REG
|
||||
uint16_t freq_half = (uint16_t) (0x3FFF & (freq_raw >> 16));
|
||||
HSwriteWord(devAddr, A1846S_FREQ_HI_REG, freq_half);
|
||||
I2Cdev::writeWord(devAddr, A1846S_FREQ_HI_REG, freq_half);
|
||||
// send bottom 16 bits to A1846S_FREQ_LO_REG
|
||||
freq_half = (uint16_t) (freq_raw & 0xFFFF);
|
||||
HSwriteWord(devAddr, A1846S_FREQ_LO_REG, freq_half);
|
||||
I2Cdev::writeWord(devAddr, A1846S_FREQ_LO_REG, freq_half);
|
||||
|
||||
if (rx_active) {
|
||||
setRX(true);
|
||||
@@ -401,7 +385,7 @@ void HamShield::setTxBand70cm() {
|
||||
uint16_t mode_len = 4;
|
||||
uint16_t bit = 11;
|
||||
|
||||
HSwriteBitsW(devAddr, A1846S_GPIO_MODE_REG, bit, mode_len, 0xF);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_GPIO_MODE_REG, bit, mode_len, 0xF);
|
||||
}
|
||||
|
||||
// clk mode
|
||||
@@ -414,10 +398,10 @@ void HamShield::setClkMode(bool LFClk){
|
||||
tx_data = 0x0FD0;
|
||||
}
|
||||
|
||||
HSwriteWord(devAddr, A1846S_CLK_MODE_REG, tx_data);
|
||||
I2Cdev::writeWord(devAddr, A1846S_CLK_MODE_REG, tx_data);
|
||||
}
|
||||
bool HamShield::getClkMode(){
|
||||
HSreadBitW(devAddr, A1846S_CLK_MODE_REG, A1846S_CLK_MODE_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_CLK_MODE_REG, A1846S_CLK_MODE_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
@@ -428,10 +412,10 @@ bool HamShield::getClkMode(){
|
||||
// 00 - 12.5kHz channel
|
||||
// 10,01 - reserved
|
||||
void HamShield::setChanMode(uint16_t mode){
|
||||
HSwriteBitsW(devAddr, A1846S_CTL_REG, A1846S_CHAN_MODE_BIT, A1846S_CHAN_MODE_LENGTH, mode);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_CTL_REG, A1846S_CHAN_MODE_BIT, A1846S_CHAN_MODE_LENGTH, mode);
|
||||
}
|
||||
uint16_t HamShield::getChanMode(){
|
||||
HSreadBitsW(devAddr, A1846S_CTL_REG, A1846S_CHAN_MODE_BIT, A1846S_CHAN_MODE_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_CTL_REG, A1846S_CHAN_MODE_BIT, A1846S_CHAN_MODE_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
*/
|
||||
@@ -444,7 +428,6 @@ void HamShield::setTX(bool on_noff){
|
||||
rx_active = false;
|
||||
setRX(false);
|
||||
|
||||
|
||||
if((radio_frequency >= 134000) && (radio_frequency <= 174000)) {
|
||||
setTxBand2m();
|
||||
}
|
||||
@@ -454,18 +437,14 @@ void HamShield::setTX(bool on_noff){
|
||||
if((radio_frequency >= 400000) && (radio_frequency <= 520000)) {
|
||||
setTxBand70cm();
|
||||
}
|
||||
// FOR HS03
|
||||
//setGpioLow(5); // V2
|
||||
//setGpioHi(4); // V1
|
||||
|
||||
|
||||
delay(50); // delay required by AU1846
|
||||
}
|
||||
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_TX_MODE_BIT, on_noff);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_TX_MODE_BIT, on_noff);
|
||||
}
|
||||
bool HamShield::getTX(){
|
||||
HSreadBitW(devAddr, A1846S_CTL_REG, A1846S_TX_MODE_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_CTL_REG, A1846S_TX_MODE_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
@@ -475,35 +454,28 @@ void HamShield::setRX(bool on_noff){
|
||||
tx_active = false;
|
||||
rx_active = true;
|
||||
setTX(false);
|
||||
// FOR HS03
|
||||
//setGpioLow(4); // V1
|
||||
//setGpioHi(5); // V2
|
||||
|
||||
setGpioLow(4); // V1
|
||||
setGpioLow(5); // V2
|
||||
|
||||
delay(50); // delay required by AU1846
|
||||
}
|
||||
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_RX_MODE_BIT, on_noff);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_RX_MODE_BIT, on_noff);
|
||||
}
|
||||
bool HamShield::getRX(){
|
||||
HSreadBitW(devAddr, A1846S_CTL_REG, A1846S_RX_MODE_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_CTL_REG, A1846S_RX_MODE_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
void HamShield::setModeTransmit(){
|
||||
// check to see if we should allow them to do this
|
||||
if(restrictions == true) {
|
||||
if(((radio_frequency > 139999) & (radio_frequency < 148001)) ||
|
||||
((radio_frequency > 218999) & (radio_frequency < 225001)) ||
|
||||
((radio_frequency > 419999) & (radio_frequency < 450001)))
|
||||
{ // we're good, so just drop down to the rest of this function
|
||||
} else {
|
||||
setRX(false);
|
||||
return;
|
||||
}
|
||||
}
|
||||
setTX(true);
|
||||
if((radio_frequency > 139999) & (radio_frequency < 148001)) { setRX(false); }
|
||||
if((radio_frequency > 218999) & (radio_frequency < 225001)) { setRX(false); }
|
||||
if((radio_frequency > 419999) & (radio_frequency < 450001)) { setRX(false); }
|
||||
} else {
|
||||
setTX(true);
|
||||
}
|
||||
}
|
||||
void HamShield::setModeReceive(){
|
||||
// turn on rx, turn off tx
|
||||
@@ -511,7 +483,7 @@ void HamShield::setModeReceive(){
|
||||
}
|
||||
void HamShield::setModeOff(){
|
||||
// turn off tx/rx
|
||||
HSwriteBitsW(devAddr, A1846S_CTL_REG, 6, 2, 0);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_CTL_REG, 6, 2, 0);
|
||||
|
||||
// turn off amplifiers
|
||||
setGpioLow(4); // V1
|
||||
@@ -530,7 +502,7 @@ void HamShield::setModeOff(){
|
||||
// 011 - sine source from tone1 and tone2
|
||||
// 100 - mic
|
||||
void HamShield::setTxSource(uint16_t tx_source){
|
||||
HSwriteBitsW(devAddr, A1846S_TX_VOICE_REG, A1846S_VOICE_SEL_BIT, A1846S_VOICE_SEL_LENGTH, tx_source);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_TX_VOICE_REG, A1846S_VOICE_SEL_BIT, A1846S_VOICE_SEL_LENGTH, tx_source);
|
||||
}
|
||||
void HamShield::setTxSourceMic(){
|
||||
setTxSource(4);
|
||||
@@ -548,7 +520,7 @@ void HamShield::setTxSourceNone(){
|
||||
setTxSource(0);
|
||||
}
|
||||
uint16_t HamShield::getTxSource(){
|
||||
HSreadBitsW(devAddr, A1846S_TX_VOICE_REG, A1846S_VOICE_SEL_BIT, A1846S_VOICE_SEL_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_TX_VOICE_REG, A1846S_VOICE_SEL_BIT, A1846S_VOICE_SEL_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
@@ -563,10 +535,10 @@ uint16_t HamShield::getTxSource(){
|
||||
// 100000: 2.45V
|
||||
// 1111111:3.13V
|
||||
void HamShield::setPABiasVoltage(uint16_t voltage){
|
||||
HSwriteBitsW(devAddr, A1846S_PABIAS_REG, A1846S_PABIAS_BIT, A1846S_PABIAS_LENGTH, voltage);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_PABIAS_REG, A1846S_PABIAS_BIT, A1846S_PABIAS_LENGTH, voltage);
|
||||
}
|
||||
uint16_t HamShield::getPABiasVoltage(){
|
||||
HSreadBitsW(devAddr, A1846S_PABIAS_REG, A1846S_PABIAS_BIT, A1846S_PABIAS_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_PABIAS_REG, A1846S_PABIAS_BIT, A1846S_PABIAS_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
*/
|
||||
@@ -595,10 +567,10 @@ uint16_t HamShield::getPABiasVoltage(){
|
||||
// 110=outer cdcss en
|
||||
// others =disable
|
||||
void HamShield::setCtcssCdcssMode(uint16_t mode){
|
||||
HSwriteBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_C_MODE_BIT, A1846S_C_MODE_LENGTH, mode);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_C_MODE_BIT, A1846S_C_MODE_LENGTH, mode);
|
||||
}
|
||||
uint16_t HamShield::getCtcssCdcssMode(){
|
||||
HSreadBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_C_MODE_BIT, A1846S_C_MODE_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_C_MODE_BIT, A1846S_C_MODE_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setInnerCtcssMode(){
|
||||
@@ -621,10 +593,10 @@ void HamShield::disableCtcssCdcss(){
|
||||
// 1 = ctcss_cmp/cdcss_cmp out via gpio
|
||||
// 0 = ctcss/cdcss sdo out vio gpio
|
||||
void HamShield::setCtcssSel(bool cmp_nsdo){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CTCSS_SEL_BIT, cmp_nsdo);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CTCSS_SEL_BIT, cmp_nsdo);
|
||||
}
|
||||
bool HamShield::getCtcssSel(){
|
||||
HSreadBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CTCSS_SEL_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CTCSS_SEL_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
@@ -632,46 +604,46 @@ bool HamShield::getCtcssSel(){
|
||||
// 1 = long (24 bit) code
|
||||
// 0 = short(23 bit) code
|
||||
void HamShield::setCdcssSel(bool long_nshort){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CDCSS_SEL_BIT, long_nshort);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CDCSS_SEL_BIT, long_nshort);
|
||||
}
|
||||
bool HamShield::getCdcssSel(){
|
||||
HSreadBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CDCSS_SEL_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CDCSS_SEL_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// Cdcss neg_det_en
|
||||
void HamShield::enableCdcssNegDet(){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_NEG_DET_EN_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_NEG_DET_EN_BIT, 1);
|
||||
}
|
||||
void HamShield::disableCdcssNegDet(){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_NEG_DET_EN_BIT, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_NEG_DET_EN_BIT, 0);
|
||||
}
|
||||
bool HamShield::getCdcssNegDetEnabled(){
|
||||
HSreadBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_NEG_DET_EN_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_NEG_DET_EN_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// Cdcss pos_det_en
|
||||
void HamShield::enableCdcssPosDet(){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_POS_DET_EN_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_POS_DET_EN_BIT, 1);
|
||||
}
|
||||
void HamShield::disableCdcssPosDet(){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_POS_DET_EN_BIT, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_POS_DET_EN_BIT, 0);
|
||||
}
|
||||
bool HamShield::getCdcssPosDetEnabled(){
|
||||
HSreadBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_POS_DET_EN_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_POS_DET_EN_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// css_det_en
|
||||
void HamShield::enableCssDet(){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CSS_DET_EN_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CSS_DET_EN_BIT, 1);
|
||||
}
|
||||
void HamShield::disableCssDet(){
|
||||
HSwriteBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CSS_DET_EN_BIT, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CSS_DET_EN_BIT, 0);
|
||||
}
|
||||
bool HamShield::getCssDetEnabled(){
|
||||
HSreadBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CSS_DET_EN_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_SUBAUDIO_REG, A1846S_CSS_DET_EN_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
@@ -683,10 +655,10 @@ void HamShield::setCtcss(float freq) {
|
||||
}
|
||||
|
||||
void HamShield::setCtcssFreq(uint16_t freq){
|
||||
HSwriteWord(devAddr, A1846S_CTCSS_FREQ_REG, freq);
|
||||
I2Cdev::writeWord(devAddr, A1846S_CTCSS_FREQ_REG, freq);
|
||||
}
|
||||
uint16_t HamShield::getCtcssFreq(){
|
||||
HSreadWord(devAddr, A1846S_CTCSS_FREQ_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_CTCSS_FREQ_REG, radio_i2c_buf);
|
||||
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
@@ -717,15 +689,15 @@ void HamShield::setCdcssCode(uint16_t code) {
|
||||
|
||||
// set registers
|
||||
uint16_t temp_code = (uint16_t) cdcss_code;
|
||||
HSwriteWord(devAddr, A1846S_CDCSS_CODE_HI_REG, temp_code);
|
||||
I2Cdev::writeWord(devAddr, A1846S_CDCSS_CODE_HI_REG, temp_code);
|
||||
temp_code = (uint16_t) (cdcss_code >> 16);
|
||||
HSwriteWord(devAddr, A1846S_CDCSS_CODE_LO_REG, temp_code);
|
||||
I2Cdev::writeWord(devAddr, A1846S_CDCSS_CODE_LO_REG, temp_code);
|
||||
}
|
||||
uint16_t HamShield::getCdcssCode() {
|
||||
uint32_t oct_code;
|
||||
HSreadWord(devAddr, A1846S_CDCSS_CODE_HI_REG, radio_i2c_buf);
|
||||
oct_code = ((uint32_t)radio_i2c_buf[0] << 16);
|
||||
HSreadWord(devAddr, A1846S_CDCSS_CODE_LO_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_CDCSS_CODE_HI_REG, radio_i2c_buf);
|
||||
oct_code = (radio_i2c_buf[0] << 16);
|
||||
I2Cdev::readWord(devAddr, A1846S_CDCSS_CODE_LO_REG, radio_i2c_buf);
|
||||
oct_code += radio_i2c_buf[0];
|
||||
|
||||
oct_code = oct_code >> 12;
|
||||
@@ -740,91 +712,89 @@ uint16_t HamShield::getCdcssCode() {
|
||||
|
||||
// SQ
|
||||
void HamShield::setSQOn(){
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_SQ_ON_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_SQ_ON_BIT, 1);
|
||||
}
|
||||
void HamShield::setSQOff(){
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_SQ_ON_BIT, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_SQ_ON_BIT, 0);
|
||||
}
|
||||
bool HamShield::getSQState(){
|
||||
HSreadBitW(devAddr, A1846S_CTL_REG, A1846S_SQ_ON_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_CTL_REG, A1846S_SQ_ON_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// SQ threshold
|
||||
void HamShield::setSQHiThresh(int16_t sq_hi_threshold){
|
||||
// Sq detect high th, rssi_cmp will be 1 when rssi>th_h_sq, unit 1dB
|
||||
uint16_t sq = 137 + sq_hi_threshold;
|
||||
HSwriteWord(devAddr, A1846S_SQ_OPEN_THRESH_REG, sq);
|
||||
void HamShield::setSQHiThresh(uint16_t sq_hi_threshold){
|
||||
// Sq detect high th, rssi_cmp will be 1 when rssi>th_h_sq, unit 1/8dB
|
||||
I2Cdev::writeWord(devAddr, A1846S_SQ_OPEN_THRESH_REG, sq_hi_threshold);
|
||||
}
|
||||
int16_t HamShield::getSQHiThresh(){
|
||||
HSreadWord(devAddr, A1846S_SQ_OPEN_THRESH_REG, radio_i2c_buf);
|
||||
uint16_t HamShield::getSQHiThresh(){
|
||||
I2Cdev::readWord(devAddr, A1846S_SQ_OPEN_THRESH_REG, radio_i2c_buf);
|
||||
|
||||
return radio_i2c_buf[0] - 137;
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setSQLoThresh(int16_t sq_lo_threshold){
|
||||
// Sq detect low th, rssi_cmp will be 0 when rssi<th_l_sq && time delay meet, unit 1 dB
|
||||
uint16_t sq = 137 + sq_lo_threshold;
|
||||
HSwriteWord(devAddr, A1846S_SQ_SHUT_THRESH_REG, sq);
|
||||
void HamShield::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
|
||||
I2Cdev::writeWord(devAddr, A1846S_SQ_SHUT_THRESH_REG, sq_lo_threshold);
|
||||
}
|
||||
int16_t HamShield::getSQLoThresh(){
|
||||
HSreadWord(devAddr, A1846S_SQ_SHUT_THRESH_REG, radio_i2c_buf);
|
||||
uint16_t HamShield::getSQLoThresh(){
|
||||
I2Cdev::readWord(devAddr, A1846S_SQ_SHUT_THRESH_REG, radio_i2c_buf);
|
||||
|
||||
return radio_i2c_buf[0] - 137;
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
// SQ out select
|
||||
void HamShield::setSQOutSel(){
|
||||
HSwriteBitW(devAddr, A1846S_SQ_OUT_SEL_REG, A1846S_SQ_OUT_SEL_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SQ_OUT_SEL_REG, A1846S_SQ_OUT_SEL_BIT, 1);
|
||||
}
|
||||
void HamShield::clearSQOutSel(){
|
||||
HSwriteBitW(devAddr, A1846S_SQ_OUT_SEL_REG, A1846S_SQ_OUT_SEL_BIT, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_SQ_OUT_SEL_REG, A1846S_SQ_OUT_SEL_BIT, 0);
|
||||
}
|
||||
bool HamShield::getSQOutSel(){
|
||||
HSreadBitW(devAddr, A1846S_SQ_OUT_SEL_REG, A1846S_SQ_OUT_SEL_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_SQ_OUT_SEL_REG, A1846S_SQ_OUT_SEL_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// VOX
|
||||
void HamShield::setVoxOn(){
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_VOX_ON_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_VOX_ON_BIT, 1);
|
||||
}
|
||||
void HamShield::setVoxOff(){
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_VOX_ON_BIT, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_VOX_ON_BIT, 0);
|
||||
}
|
||||
bool HamShield::getVoxOn(){
|
||||
HSreadBitW(devAddr, A1846S_CTL_REG, A1846S_VOX_ON_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_CTL_REG, A1846S_VOX_ON_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// Vox Threshold
|
||||
void HamShield::setVoxOpenThresh(uint16_t vox_open_thresh){
|
||||
// When vssi > th_h_vox, then vox will be 1(unit mV )
|
||||
HSwriteWord(devAddr, A1846S_TH_H_VOX_REG, vox_open_thresh);
|
||||
I2Cdev::writeWord(devAddr, A1846S_TH_H_VOX_REG, vox_open_thresh);
|
||||
}
|
||||
uint16_t HamShield::getVoxOpenThresh(){
|
||||
HSreadWord(devAddr, A1846S_TH_H_VOX_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_TH_H_VOX_REG, radio_i2c_buf);
|
||||
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setVoxShutThresh(uint16_t vox_shut_thresh){
|
||||
// When vssi < th_l_vox && time delay meet, then vox will be 0 (unit mV )
|
||||
HSwriteWord(devAddr, A1846S_TH_L_VOX_REG, vox_shut_thresh);
|
||||
I2Cdev::writeWord(devAddr, A1846S_TH_L_VOX_REG, vox_shut_thresh);
|
||||
}
|
||||
uint16_t HamShield::getVoxShutThresh(){
|
||||
HSreadWord(devAddr, A1846S_TH_L_VOX_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_TH_L_VOX_REG, radio_i2c_buf);
|
||||
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
// Tail Noise
|
||||
void HamShield::enableTailNoiseElim(){
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_TAIL_ELIM_EN_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_TAIL_ELIM_EN_BIT, 1);
|
||||
}
|
||||
void HamShield::disableTailNoiseElim(){
|
||||
HSwriteBitW(devAddr, A1846S_CTL_REG, A1846S_TAIL_ELIM_EN_BIT, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_CTL_REG, A1846S_TAIL_ELIM_EN_BIT, 1);
|
||||
}
|
||||
bool HamShield::getTailNoiseElimEnabled(){
|
||||
HSreadBitW(devAddr, A1846S_CTL_REG, A1846S_TAIL_ELIM_EN_BIT, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_CTL_REG, A1846S_TAIL_ELIM_EN_BIT, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
@@ -835,100 +805,100 @@ bool HamShield::getTailNoiseElimEnabled(){
|
||||
// 10 = 240 degree shift
|
||||
// 11 = reserved
|
||||
void HamShield::setShiftSelect(uint16_t shift_sel){
|
||||
HSwriteBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_SHIFT_SEL_BIT, A1846S_SHIFT_SEL_LENGTH, shift_sel);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_SHIFT_SEL_BIT, A1846S_SHIFT_SEL_LENGTH, shift_sel);
|
||||
}
|
||||
uint16_t HamShield::getShiftSelect(){
|
||||
HSreadBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_SHIFT_SEL_BIT, A1846S_SHIFT_SEL_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_SUBAUDIO_REG, A1846S_SHIFT_SEL_BIT, A1846S_SHIFT_SEL_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
// DTMF
|
||||
void HamShield::setDTMFC0(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C0_BIT, A1846S_DTMF_C0_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C0_BIT, A1846S_DTMF_C0_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC0() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C0_BIT, A1846S_DTMF_C0_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C0_BIT, A1846S_DTMF_C0_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC1(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C1_BIT, A1846S_DTMF_C1_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C1_BIT, A1846S_DTMF_C1_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC1() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C1_BIT, A1846S_DTMF_C1_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C01_REG, A1846S_DTMF_C1_BIT, A1846S_DTMF_C1_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC2(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C2_BIT, A1846S_DTMF_C2_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C2_BIT, A1846S_DTMF_C2_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC2() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C2_BIT, A1846S_DTMF_C2_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C2_BIT, A1846S_DTMF_C2_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC3(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C3_BIT, A1846S_DTMF_C3_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C3_BIT, A1846S_DTMF_C3_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC3() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C3_BIT, A1846S_DTMF_C3_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C23_REG, A1846S_DTMF_C3_BIT, A1846S_DTMF_C3_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC4(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C4_BIT, A1846S_DTMF_C4_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C4_BIT, A1846S_DTMF_C4_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC4() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C4_BIT, A1846S_DTMF_C4_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C4_BIT, A1846S_DTMF_C4_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC5(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C5_BIT, A1846S_DTMF_C5_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C5_BIT, A1846S_DTMF_C5_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC5() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C5_BIT, A1846S_DTMF_C5_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C45_REG, A1846S_DTMF_C5_BIT, A1846S_DTMF_C5_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC6(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C6_BIT, A1846S_DTMF_C6_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C6_BIT, A1846S_DTMF_C6_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC6() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C6_BIT, A1846S_DTMF_C6_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C6_BIT, A1846S_DTMF_C6_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setDTMFC7(uint16_t freq) {
|
||||
HSwriteBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C7_BIT, A1846S_DTMF_C7_LENGTH, freq);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C7_BIT, A1846S_DTMF_C7_LENGTH, freq);
|
||||
}
|
||||
uint16_t HamShield::getDTMFC7() {
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C7_BIT, A1846S_DTMF_C7_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_C67_REG, A1846S_DTMF_C7_BIT, A1846S_DTMF_C7_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
// TX FM deviation
|
||||
void HamShield::setFMVoiceCssDeviation(uint16_t deviation){
|
||||
HSwriteBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_VOICE_BIT, A1846S_FM_DEV_VOICE_LENGTH, deviation);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_VOICE_BIT, A1846S_FM_DEV_VOICE_LENGTH, deviation);
|
||||
}
|
||||
uint16_t HamShield::getFMVoiceCssDeviation(){
|
||||
HSreadBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_VOICE_BIT, A1846S_FM_DEV_VOICE_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_VOICE_BIT, A1846S_FM_DEV_VOICE_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setFMCssDeviation(uint16_t deviation){
|
||||
HSwriteBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_CSS_BIT, A1846S_FM_DEV_CSS_LENGTH, deviation);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_CSS_BIT, A1846S_FM_DEV_CSS_LENGTH, deviation);
|
||||
}
|
||||
uint16_t HamShield::getFMCssDeviation(){
|
||||
HSreadBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_CSS_BIT, A1846S_FM_DEV_CSS_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_FM_DEV_REG, A1846S_FM_DEV_CSS_BIT, A1846S_FM_DEV_CSS_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
// RX voice range
|
||||
void HamShield::setVolume1(uint16_t volume){
|
||||
HSwriteBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_1_BIT, A1846S_RX_VOL_1_LENGTH, volume);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_1_BIT, A1846S_RX_VOL_1_LENGTH, volume);
|
||||
}
|
||||
uint16_t HamShield::getVolume1(){
|
||||
HSreadBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_1_BIT, A1846S_RX_VOL_1_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_1_BIT, A1846S_RX_VOL_1_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setVolume2(uint16_t volume){
|
||||
HSwriteBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_2_BIT, A1846S_RX_VOL_2_LENGTH, volume);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_2_BIT, A1846S_RX_VOL_2_LENGTH, volume);
|
||||
}
|
||||
uint16_t HamShield::getVolume2(){
|
||||
HSreadBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_2_BIT, A1846S_RX_VOL_2_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_RX_VOLUME_REG, A1846S_RX_VOL_2_BIT, A1846S_RX_VOL_2_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
@@ -937,7 +907,7 @@ void HamShield::setGpioMode(uint16_t gpio, uint16_t mode){
|
||||
uint16_t mode_len = 2;
|
||||
uint16_t bit = gpio*2 + 1;
|
||||
|
||||
HSwriteBitsW(devAddr, A1846S_GPIO_MODE_REG, bit, mode_len, mode);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_GPIO_MODE_REG, bit, mode_len, mode);
|
||||
}
|
||||
void HamShield::setGpioHiZ(uint16_t gpio){
|
||||
setGpioMode(gpio, 0);
|
||||
@@ -955,33 +925,33 @@ uint16_t HamShield::getGpioMode(uint16_t gpio){
|
||||
uint16_t mode_len = 2;
|
||||
uint16_t bit = gpio*2 + 1;
|
||||
|
||||
HSreadBitsW(devAddr, A1846S_GPIO_MODE_REG, bit, mode_len, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_GPIO_MODE_REG, bit, mode_len, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
uint16_t HamShield::getGpios(){
|
||||
HSreadWord(devAddr, A1846S_GPIO_MODE_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_GPIO_MODE_REG, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
// Int
|
||||
void HamShield::enableInterrupt(uint16_t interrupt){
|
||||
HSwriteBitW(devAddr, A1846S_INT_MODE_REG, interrupt, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_INT_MODE_REG, interrupt, 1);
|
||||
}
|
||||
void HamShield::disableInterrupt(uint16_t interrupt){
|
||||
HSwriteBitW(devAddr, A1846S_INT_MODE_REG, interrupt, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_INT_MODE_REG, interrupt, 0);
|
||||
}
|
||||
bool HamShield::getInterruptEnabled(uint16_t interrupt){
|
||||
HSreadBitW(devAddr, A1846S_INT_MODE_REG, interrupt, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_INT_MODE_REG, interrupt, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// ST mode
|
||||
void HamShield::setStMode(uint16_t mode){
|
||||
HSwriteBitsW(devAddr, A1846S_CTL_REG, A1846S_ST_MODE_BIT, A1846S_ST_MODE_LENGTH, mode);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_CTL_REG, A1846S_ST_MODE_BIT, A1846S_ST_MODE_LENGTH, mode);
|
||||
}
|
||||
uint16_t HamShield::getStMode(){
|
||||
HSreadBitsW(devAddr, A1846S_CTL_REG, A1846S_ST_MODE_BIT, A1846S_ST_MODE_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_CTL_REG, A1846S_ST_MODE_BIT, A1846S_ST_MODE_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
void HamShield::setStFullAuto(){
|
||||
@@ -996,31 +966,31 @@ setStMode(0);
|
||||
|
||||
// Pre-emphasis, De-emphasis filter
|
||||
void HamShield::bypassPreDeEmph(){
|
||||
HSwriteBitW(devAddr, A1846S_EMPH_FILTER_REG, A1846S_EMPH_FILTER_EN, 1);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_EMPH_FILTER_REG, A1846S_EMPH_FILTER_EN, 1);
|
||||
}
|
||||
void HamShield::usePreDeEmph(){
|
||||
HSwriteBitW(devAddr, A1846S_EMPH_FILTER_REG, A1846S_EMPH_FILTER_EN, 0);
|
||||
I2Cdev::writeBitW(devAddr, A1846S_EMPH_FILTER_REG, A1846S_EMPH_FILTER_EN, 0);
|
||||
}
|
||||
bool HamShield::getPreDeEmphEnabled(){
|
||||
HSreadBitW(devAddr, A1846S_EMPH_FILTER_REG, A1846S_EMPH_FILTER_EN, radio_i2c_buf);
|
||||
I2Cdev::readBitW(devAddr, A1846S_EMPH_FILTER_REG, A1846S_EMPH_FILTER_EN, radio_i2c_buf);
|
||||
return (radio_i2c_buf[0] != 0);
|
||||
}
|
||||
|
||||
// Read Only Status Registers
|
||||
int16_t HamShield::readRSSI(){
|
||||
HSreadBitsW(devAddr, A1846S_RSSI_REG, A1846S_RSSI_BIT, A1846S_RSSI_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_RSSI_REG, A1846S_RSSI_BIT, A1846S_RSSI_LENGTH, radio_i2c_buf);
|
||||
|
||||
int16_t rssi = (radio_i2c_buf[0] & 0xFF) - 137;
|
||||
int16_t rssi = (radio_i2c_buf[0] & 0x3FF) - 137;
|
||||
return rssi;
|
||||
}
|
||||
uint16_t HamShield::readVSSI(){
|
||||
HSreadWord(devAddr, A1846S_VSSI_REG, radio_i2c_buf);
|
||||
I2Cdev::readWord(devAddr, A1846S_VSSI_REG, radio_i2c_buf);
|
||||
|
||||
return radio_i2c_buf[0] & 0x7FF; // only need lowest 10 bits
|
||||
}
|
||||
uint16_t HamShield::readDTMFIndex(){
|
||||
// TODO: may want to split this into two (index1 and index2)
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_RX_REG, A1846S_DTMF_INDEX_BIT, A1846S_DTMF_INDEX_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_RX_REG, A1846S_DTMF_INDEX_BIT, A1846S_DTMF_INDEX_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
uint16_t HamShield::readDTMFCode(){
|
||||
@@ -1028,7 +998,7 @@ uint16_t HamShield::readDTMFCode(){
|
||||
// 4:f1+f4, 5:f1+f5, 6:f1+f6, B:f1+f7,
|
||||
// 7:f2+f4, 8:f2+f5, 9:f2+f6, C:f2+f7,
|
||||
// E(*):f3+f4, 0:f3+f5, F(#):f3+f6, D:f3+f7
|
||||
HSreadBitsW(devAddr, A1846S_DTMF_RX_REG, A1846S_DTMF_CODE_BIT, A1846S_DTMF_CODE_LENGTH, radio_i2c_buf);
|
||||
I2Cdev::readBitsW(devAddr, A1846S_DTMF_RX_REG, A1846S_DTMF_CODE_BIT, A1846S_DTMF_CODE_LENGTH, radio_i2c_buf);
|
||||
return radio_i2c_buf[0];
|
||||
}
|
||||
|
||||
@@ -1040,9 +1010,9 @@ void HamShield::setRfPower(uint8_t pwr) {
|
||||
}
|
||||
|
||||
// turn off tx/rx
|
||||
HSwriteBitsW(devAddr, A1846S_CTL_REG, 6, 2, 0);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_CTL_REG, 6, 2, 0);
|
||||
|
||||
HSwriteBitsW(devAddr, A1846S_PABIAS_REG, A1846S_PADRV_BIT, A1846S_PADRV_LENGTH, pwr);
|
||||
I2Cdev::writeBitsW(devAddr, A1846S_PABIAS_REG, A1846S_PADRV_BIT, A1846S_PADRV_LENGTH, pwr);
|
||||
|
||||
if (rx_active) {
|
||||
setRX(true);
|
||||
@@ -1294,13 +1264,10 @@ void HamShield::morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]) {
|
||||
if(buffer[i] == ' ') {
|
||||
// We delay by 4 here, if we previously sent a symbol. Otherwise 7.
|
||||
// This could probably just be always 7 and go relatively unnoticed.
|
||||
if(prev == 0 || prev == ' '){
|
||||
tone(HAMSHIELD_PWM_PIN, 6000, HAMSHIELD_MORSE_DOT * 7);
|
||||
if(prev == 0 || prev == ' ')
|
||||
delay(HAMSHIELD_MORSE_DOT*7);
|
||||
} else {
|
||||
tone(HAMSHIELD_PWM_PIN, 6000, HAMSHIELD_MORSE_DOT * 4);
|
||||
else
|
||||
delay(HAMSHIELD_MORSE_DOT*4);
|
||||
}
|
||||
continue;
|
||||
}
|
||||
// Otherwise, lookup our character symbol
|
||||
@@ -1308,19 +1275,17 @@ void HamShield::morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]) {
|
||||
if(bits) { // If it is a valid character...
|
||||
do {
|
||||
if(bits & 1) {
|
||||
tone(HAMSHIELD_PWM_PIN, 600, HAMSHIELD_MORSE_DOT * 3);
|
||||
tone(HAMSHIELD_PWM_PIN, 1000, HAMSHIELD_MORSE_DOT * 3);
|
||||
delay(HAMSHIELD_MORSE_DOT*3);
|
||||
} else {
|
||||
tone(HAMSHIELD_PWM_PIN, 600, HAMSHIELD_MORSE_DOT);
|
||||
tone(HAMSHIELD_PWM_PIN, 1000, HAMSHIELD_MORSE_DOT);
|
||||
delay(HAMSHIELD_MORSE_DOT);
|
||||
}
|
||||
tone(HAMSHIELD_PWM_PIN, 6000, HAMSHIELD_MORSE_DOT);
|
||||
delay(HAMSHIELD_MORSE_DOT);
|
||||
bits >>= 1; // Shift into the next symbol
|
||||
} while(bits != 1); // Wait for 1 termination to be all we have left
|
||||
}
|
||||
// End of character
|
||||
tone(HAMSHIELD_PWM_PIN, 6000, HAMSHIELD_MORSE_DOT * 3);
|
||||
delay(HAMSHIELD_MORSE_DOT * 3);
|
||||
}
|
||||
return;
|
||||
@@ -8,10 +8,11 @@
|
||||
#ifndef _HAMSHIELD_H_
|
||||
#define _HAMSHIELD_H_
|
||||
|
||||
#include "HamShield_comms.h"
|
||||
//#include "SimpleFIFO.h"
|
||||
//#include "AFSK.h"
|
||||
//#include "DDS.h"
|
||||
//#include "I2Cdev_rda.h"
|
||||
#include "I2Cdev.h"
|
||||
#include "SimpleFIFO.h"
|
||||
#include "AFSK.h"
|
||||
#include "DDS.h"
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
// HamShield constants
|
||||
@@ -22,10 +23,17 @@
|
||||
#define HAMSHIELD_PWM_PIN 3 // Pin assignment for PWM output
|
||||
#define HAMSHIELD_EMPTY_CHANNEL_RSSI -110 // Default threshold where channel is considered "clear"
|
||||
|
||||
#define HAMSHIELD_AFSK_RX_FIFO_LEN 16
|
||||
|
||||
// button modes
|
||||
#define PTT_MODE 1
|
||||
#define RESET_MODE 2
|
||||
|
||||
// Device Constants
|
||||
#define A1846S_DEV_ADDR_SENHIGH 0b0101110
|
||||
#define A1846S_DEV_ADDR_SENLOW 0b1110001
|
||||
|
||||
|
||||
// Device Registers
|
||||
#define A1846S_CTL_REG 0x30 // control register
|
||||
#define A1846S_CLK_MODE_REG 0x04 // clk_mode
|
||||
@@ -179,7 +187,7 @@
|
||||
#define A1846S_VOX_FLAG_BIT 0 // vox out from dsp
|
||||
|
||||
// Bitfields for A1846S_RSSI_REG
|
||||
#define A1846S_RSSI_BIT 15 // RSSI readings <7:0>
|
||||
#define A1846S_RSSI_BIT 15 // RSSI readings <9:0>
|
||||
#define A1846S_RSSI_LENGTH 8
|
||||
|
||||
// Bitfields for A1846S_VSSI_REG
|
||||
@@ -233,7 +241,7 @@
|
||||
|
||||
|
||||
#define ROBOT8BW 2
|
||||
#define SC2_180 55
|
||||
#define SC2-180 55
|
||||
#define MARTIN1 44
|
||||
|
||||
// RTTY Frequencies
|
||||
@@ -254,7 +262,7 @@ class HamShield {
|
||||
static HamShield *sHamShield; // HamShield singleton, used for ISRs mostly
|
||||
|
||||
HamShield();
|
||||
HamShield(uint8_t cs_pin);
|
||||
HamShield(uint8_t address);
|
||||
|
||||
void initialize();
|
||||
bool testConnection();
|
||||
@@ -366,10 +374,10 @@ class HamShield {
|
||||
bool getSQState();
|
||||
|
||||
// SQ threshold
|
||||
void setSQHiThresh(int16_t sq_hi_threshold); // Sq detect high th, rssi_cmp will be 1 when rssi>th_h_sq, unit 1dB
|
||||
int16_t getSQHiThresh();
|
||||
void setSQLoThresh(int16_t sq_lo_threshold); // Sq detect low th, rssi_cmp will be 0 when rssi<th_l_sq && time delay meet, unit 1dB
|
||||
int16_t getSQLoThresh();
|
||||
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 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 getSQLoThresh();
|
||||
|
||||
// SQ out select
|
||||
void setSQOutSel();
|
||||
@@ -489,17 +497,15 @@ class HamShield {
|
||||
void toneWait(uint16_t freq, long timer);
|
||||
void toneWaitU(uint16_t freq, long timer);
|
||||
bool parityCalc(int code);
|
||||
// void AFSKOut(char buffer[80]);
|
||||
|
||||
|
||||
|
||||
//TODO: split AFSK out so it can be left out
|
||||
// AFSK routines
|
||||
//bool AFSKStart();
|
||||
//bool AFSKEnabled() { return afsk.enabled(); }
|
||||
//bool AFSKStop();
|
||||
//bool AFSKOut(const char *);
|
||||
bool AFSKStart();
|
||||
bool AFSKEnabled() { return afsk.enabled(); }
|
||||
bool AFSKStop();
|
||||
bool AFSKOut(const char *);
|
||||
|
||||
//class AFSK afsk;
|
||||
class AFSK afsk;
|
||||
|
||||
private:
|
||||
uint8_t devAddr;
|
||||
@@ -507,11 +513,11 @@ class HamShield {
|
||||
bool tx_active;
|
||||
bool rx_active;
|
||||
uint32_t radio_frequency;
|
||||
/* uint32_t FRS[];
|
||||
uint32_t FRS[];
|
||||
uint32_t GMRS[];
|
||||
uint32_t MURS[];
|
||||
uint32_t WX[];
|
||||
*/
|
||||
|
||||
// private utility functions
|
||||
// these functions should not be called in the Arduino sketch
|
||||
// just use the above public functions to do everything
|
||||
1457
I2Cdev.cpp
Normal file
1457
I2Cdev.cpp
Normal file
File diff suppressed because it is too large
Load Diff
281
I2Cdev.h
Normal file
281
I2Cdev.h
Normal file
@@ -0,0 +1,281 @@
|
||||
// I2Cdev library collection - Main I2C device class header file
|
||||
// Abstracts bit and byte I2C R/W functions into a convenient class
|
||||
// 2013-06-05 by Jeff Rowberg <jeff@rowberg.net>
|
||||
//
|
||||
// Changelog:
|
||||
// 2015-10-30 - simondlevy : support i2c_t3 for Teensy3.1
|
||||
// 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_H_
|
||||
#define _I2CDEV_H_
|
||||
|
||||
// -----------------------------------------------------------------------------
|
||||
// I2C interface implementation setting
|
||||
// -----------------------------------------------------------------------------
|
||||
#ifndef I2CDEV_IMPLEMENTATION
|
||||
#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE
|
||||
//#define I2CDEV_IMPLEMENTATION I2CDEV_BUILTIN_FASTWIRE
|
||||
#endif // I2CDEV_IMPLEMENTATION
|
||||
|
||||
// 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 defined(CORE_TEENSY) && defined(__MK20DX256__)
|
||||
#include <i2c_t3.h>
|
||||
#define BUFFER_LENGTH 32
|
||||
#elif I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
|
||||
#include <Wire.h>
|
||||
#endif
|
||||
#if I2CDEV_IMPLEMENTATION == I2CDEV_I2CMASTER_LIBRARY
|
||||
#include <I2C.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef SPARK
|
||||
#include <spark_wiring_i2c.h>
|
||||
#define ARDUINO 101
|
||||
#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_H_ */
|
||||
88
KISS.cpp
Normal file
88
KISS.cpp
Normal 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
35
KISS.h
Normal 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_ */
|
||||
@@ -1,10 +1,6 @@
|
||||
# HamShield
|
||||
|
||||
WARNING: The dev branch is not guaranteed to work. Please use caution if you choose to use that branch.
|
||||
|
||||
All of the AFSK, DDS, etc. files have been moved to the in Progress directory. These files collectively use twice as much memory as the essential HamShield functions. The current plan is to make sure these are only included if they're going to be used. We'll also be adapting them to make them more friendly to non-Uno Arduinos. Stay tuned for those changes.
|
||||
|
||||
The master branch is intended for use with HamShield hardware -09 and above.
|
||||
Use the HS04 branch for old (pre -09) versions of the hardware.
|
||||
|
||||
HamShield Arduino Library and Example Sketches
|
||||
|
||||
|
||||
89
SimpleFIFO.h
Normal file
89
SimpleFIFO.h
Normal 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
|
||||
136
examples/AFSK-PacketTester/AFSK-PacketTester.ino
Normal file
136
examples/AFSK-PacketTester/AFSK-PacketTester.ino
Normal file
@@ -0,0 +1,136 @@
|
||||
/* Serial glue to send messages over APRS
|
||||
*
|
||||
* To do: add message receive code
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#define DDS_REFCLK_DEFAULT 9600
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <Wire.h>
|
||||
#include <avr/wdt.h>
|
||||
|
||||
//TODO: move these into library
|
||||
#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);
|
||||
Wire.begin();
|
||||
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
|
||||
@@ -1,23 +1,14 @@
|
||||
/* Hamshield
|
||||
* Example: AFSK Serial Messenger
|
||||
* Serial glue to send messages over APRS. You will need a
|
||||
* seperate AFSK receiver to test the output of this example.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. After uploading this program
|
||||
* to your Arduino, open the Serial Monitor to monitor. Type
|
||||
* a message under 254 characters into the bar at the top of
|
||||
* the monitor. Click the "Send" button. Check for output on
|
||||
* AFSK receiver.
|
||||
|
||||
* NOTE: add message receive code
|
||||
*/
|
||||
/* Serial glue to send messages over APRS
|
||||
*
|
||||
* To do: add message receive code
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#define DDS_REFCLK_DEFAULT 9600
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include <packet.h>
|
||||
#include <Wire.h>
|
||||
#include <avr/wdt.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
@@ -26,7 +17,6 @@
|
||||
|
||||
HamShield radio;
|
||||
DDS dds;
|
||||
AFSK afsk;
|
||||
String messagebuff = "";
|
||||
String origin_call = "";
|
||||
String destination_call = "";
|
||||
@@ -46,13 +36,13 @@ void setup() {
|
||||
// turn on the radio
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Serial.begin(9600);
|
||||
|
||||
Serial.begin(115200);
|
||||
Wire.begin();
|
||||
radio.initialize();
|
||||
radio.frequency(145570);
|
||||
radio.setRfPower(0);
|
||||
dds.start();
|
||||
afsk.start(&dds);
|
||||
radio.afsk.start(&dds);
|
||||
delay(100);
|
||||
Serial.println("HELLO");
|
||||
}
|
||||
@@ -94,13 +84,13 @@ void prepMessage() {
|
||||
|
||||
textmessage = "";
|
||||
|
||||
bool ret = afsk.putTXPacket(packet);
|
||||
bool ret = radio.afsk.putTXPacket(packet);
|
||||
|
||||
if(afsk.txReady()) {
|
||||
if(radio.afsk.txReady()) {
|
||||
Serial.println(F("txReady"));
|
||||
//radio.setModeTransmit();
|
||||
//delay(100);
|
||||
if(afsk.txStart()) {
|
||||
if(radio.afsk.txStart()) {
|
||||
Serial.println(F("txStart"));
|
||||
} else {
|
||||
radio.setModeReceive();
|
||||
@@ -111,7 +101,7 @@ void prepMessage() {
|
||||
// Wait up to 2.5 seconds to finish sending, and stop transmitter.
|
||||
// TODO: This is hackery.
|
||||
for(int i = 0; i < 500; i++) {
|
||||
if(afsk.encoder.isDone())
|
||||
if(radio.afsk.encoder.isDone())
|
||||
break;
|
||||
delay(50);
|
||||
}
|
||||
@@ -139,8 +129,8 @@ ISR(ADC_vect) {
|
||||
//PORTD |= _BV(2); // Diagnostic pin (D2)
|
||||
dds.clockTick();
|
||||
if(++tcnt == 1) {
|
||||
if(afsk.encoder.isSending()) {
|
||||
afsk.timer();
|
||||
if(radio.afsk.encoder.isSending()) {
|
||||
radio.afsk.timer();
|
||||
}
|
||||
tcnt = 0;
|
||||
}
|
||||
106
examples/AFSKSend/AFSKSend.ino
Normal file
106
examples/AFSKSend/AFSKSend.ino
Normal file
@@ -0,0 +1,106 @@
|
||||
#include <HamShield.h>
|
||||
#include <Wire.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);
|
||||
Wire.begin();
|
||||
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);
|
||||
}
|
||||
@@ -1,128 +0,0 @@
|
||||
/* Hamshield
|
||||
* Example: AFSK Packet Tester
|
||||
* This example sends AFSK test data. You will need a seperate
|
||||
* AFSK receiver to test the output of this example.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, open the Serial Monitor to
|
||||
* monitor the process of the HamShield. Check for output on
|
||||
* AFSK receiver.
|
||||
|
||||
* Note: add message receive code
|
||||
*/
|
||||
|
||||
#define DDS_REFCLK_DEFAULT 9600
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include <packet.h>
|
||||
#include <avr/wdt.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
#define SWITCH_PIN 2
|
||||
|
||||
HamShield radio;
|
||||
DDS dds;
|
||||
AFSK afsk;
|
||||
String messagebuff = "";
|
||||
String origin_call = "";
|
||||
String destination_call = "";
|
||||
String textmessage = "";
|
||||
int msgptr = 0;
|
||||
|
||||
void setup() {
|
||||
// NOTE: if not using PWM out, it should be held low to avoid tx noise
|
||||
pinMode(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(9600);
|
||||
|
||||
radio.initialize();
|
||||
radio.frequency(144390);
|
||||
radio.setRfPower(0);
|
||||
dds.start();
|
||||
afsk.start(&dds);
|
||||
delay(100);
|
||||
Serial.println("HELLO");
|
||||
}
|
||||
|
||||
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 = afsk.putTXPacket(packet);
|
||||
|
||||
if(afsk.txReady()) {
|
||||
Serial.println(F("txReady"));
|
||||
radio.setModeTransmit();
|
||||
//delay(100);
|
||||
if(afsk.txStart()) {
|
||||
Serial.println(F("txStart"));
|
||||
} else {
|
||||
radio.setModeReceive();
|
||||
}
|
||||
}
|
||||
// Wait 2 seconds before we send our beacon again.
|
||||
Serial.println("tick");
|
||||
// Wait up to 2.5 seconds to finish sending, and stop transmitter.
|
||||
// TODO: This is hackery.
|
||||
for(int i = 0; i < 500; i++) {
|
||||
if(afsk.encoder.isDone())
|
||||
break;
|
||||
delay(50);
|
||||
}
|
||||
Serial.println("Done sending");
|
||||
radio.setModeReceive();
|
||||
}
|
||||
|
||||
ISR(TIMER2_OVF_vect) {
|
||||
TIFR2 = _BV(TOV2);
|
||||
static uint8_t tcnt = 0;
|
||||
if(++tcnt == 8) {
|
||||
dds.clockTick();
|
||||
tcnt = 0;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(ADC_vect) {
|
||||
static uint8_t tcnt = 0;
|
||||
TIFR1 = _BV(ICF1); // Clear the timer flag
|
||||
dds.clockTick();
|
||||
if(++tcnt == 1) {
|
||||
if(afsk.encoder.isSending()) {
|
||||
afsk.timer();
|
||||
}
|
||||
tcnt = 0;
|
||||
}
|
||||
}
|
||||
0
examples/APRS_Beacon/1200.wav → examples/APRS-Beacon/1200.wav
Normal file → Executable file
0
examples/APRS_Beacon/1200.wav → examples/APRS-Beacon/1200.wav
Normal file → Executable file
0
examples/APRS_Beacon/2200.wav → examples/APRS-Beacon/2200.wav
Normal file → Executable file
0
examples/APRS_Beacon/2200.wav → examples/APRS-Beacon/2200.wav
Normal file → Executable file
@@ -1,20 +1,5 @@
|
||||
/* Hamshield
|
||||
* Example: AX25 Receive
|
||||
* This example receives AFSK test data. You will need seperate
|
||||
* AFSK equipment to send data for this example.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then to
|
||||
* your computer via USB. After uploading this program to your
|
||||
* Arduino, open the Serial Monitor so you will see the AFSK
|
||||
* packet. Send AFSK packet from AFSK equipment at 145.01MHz.
|
||||
|
||||
* Note: add message receive code
|
||||
*/
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include <packet.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -22,7 +7,6 @@
|
||||
|
||||
HamShield radio;
|
||||
DDS dds;
|
||||
AFSK afsk;
|
||||
|
||||
void setup() {
|
||||
// NOTE: if not using PWM out, it should be held low to avoid tx noise
|
||||
@@ -38,7 +22,7 @@ void setup() {
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Serial.begin(9600);
|
||||
|
||||
Wire.begin();
|
||||
Serial.println(F("Radio test connection"));
|
||||
Serial.println(radio.testConnection(), DEC);
|
||||
Serial.println(F("Initialize"));
|
||||
@@ -46,6 +30,7 @@ void setup() {
|
||||
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): "));
|
||||
@@ -53,12 +38,14 @@ void setup() {
|
||||
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);
|
||||
afsk.start(&dds);
|
||||
radio.afsk.start(&dds);
|
||||
Serial.println(F("Starting..."));
|
||||
delay(100);
|
||||
dds.setAmplitude(255);
|
||||
@@ -66,11 +53,11 @@ void setup() {
|
||||
|
||||
uint32_t last = 0;
|
||||
void loop() {
|
||||
if(afsk.decoder.read() || afsk.rxPacketCount()) {
|
||||
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(afsk.rxPacketCount()) {
|
||||
AFSK::Packet *packet = afsk.getRXPacket();
|
||||
while(radio.afsk.rxPacketCount()) {
|
||||
AFSK::Packet *packet = radio.afsk.getRXPacket();
|
||||
Serial.print(F("Packet: "));
|
||||
if(packet) {
|
||||
packet->printPacket(&Serial);
|
||||
@@ -86,6 +73,6 @@ ISR(ADC_vect) {
|
||||
TIFR1 = _BV(ICF1); // Clear the timer flag
|
||||
//PORTD |= _BV(2); // Diagnostic pin (D2)
|
||||
//dds.clockTick();
|
||||
afsk.timer();
|
||||
radio.afsk.timer();
|
||||
//PORTD &= ~(_BV(2)); // Pin D2 off again
|
||||
}
|
||||
|
||||
@@ -1,21 +1,9 @@
|
||||
/* Hamshield
|
||||
* Example: Crystal Calibration
|
||||
* This example allows you to calibrate the crystal clock
|
||||
* through the Arduino Serial Monitor.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, open the Serial Monitor.
|
||||
* Type 'h' into the bar at the top of the Serial Monitor
|
||||
* and click the "Send" button for more instructions.
|
||||
*/
|
||||
|
||||
#define DDS_REFCLK_DEFAULT 38400
|
||||
#define DDS_REFCLK_OFFSET 0
|
||||
#define DDS_DEBUG_SERIAL
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -38,10 +26,10 @@ void setup() {
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Serial.begin(9600);
|
||||
|
||||
Wire.begin();
|
||||
radio.initialize();
|
||||
radio.setRfPower(0);
|
||||
radio.frequency(145050);
|
||||
radio.setFrequency(145050);
|
||||
|
||||
dds.start();
|
||||
dds.setFrequency(1200);
|
||||
@@ -118,7 +106,7 @@ void loop() {
|
||||
}
|
||||
while(Serial.available()) {
|
||||
char c = Serial.read();
|
||||
Serial.println(c);
|
||||
Serial.print(c);
|
||||
switch(c) {
|
||||
case 'h':
|
||||
Serial.println(F("Commands:"));
|
||||
|
||||
@@ -1,18 +1,7 @@
|
||||
/* Hamshield
|
||||
* Example: DDS
|
||||
* This is a simple example to show hot to transmit arbitrary
|
||||
* tones. In this case, the sketh alternates between 1200Hz
|
||||
* and 2200Hz at 1s intervals.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. Upload this program
|
||||
* to your Arduino. To test, set a HandyTalkie to 438MHz. You
|
||||
* should hear two alternating tones.
|
||||
*/
|
||||
|
||||
#define DDS_REFCLK_DEFAULT 9600
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include <Wire.h>
|
||||
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -34,9 +23,10 @@ void setup() {
|
||||
// turn on radio
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
radio.initialize();
|
||||
radio.setRfPower(0);
|
||||
radio.frequency(438000);
|
||||
radio.setFrequency(145060);
|
||||
radio.setModeTransmit();
|
||||
dds.start();
|
||||
dds.playWait(600, 3000);
|
||||
@@ -60,8 +50,10 @@ 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
|
||||
|
||||
@@ -1,28 +1,19 @@
|
||||
/* Hamshield
|
||||
* Example: Morse Code Beacon
|
||||
* Test beacon will transmit and wait 30 seconds.
|
||||
* Beacon will check to see if the channel is clear before it
|
||||
* will transmit.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, open the Serial Monitor to
|
||||
* monitor the status of the beacon. To test, set a HandyTalkie
|
||||
* to 438MHz. You should hear the message " KC7IBT ARDUINO
|
||||
* HAMSHIELD" in morse code.
|
||||
/*
|
||||
Morse Code Beacon
|
||||
|
||||
* NOTE: Radio chip audio AGC too slow in responding to tones,
|
||||
* worked around by playing a 6khz tone between actual dits/dahs.
|
||||
* Should work on adjusting AGC to not require this.
|
||||
Test beacon will transmit and wait 30 seconds.
|
||||
Beacon will check to see if the channel is clear before it will transmit.
|
||||
*/
|
||||
|
||||
#define DDS_REFCLK_DEFAULT 9600
|
||||
// Include the HamSheild and Wire (I2C) libraries
|
||||
#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'
|
||||
HamShield radio;
|
||||
|
||||
// Run our start up things here
|
||||
@@ -44,6 +35,9 @@ void setup() {
|
||||
// Send a quick serial string
|
||||
Serial.println("HamShield FM Beacon Example Sketch");
|
||||
|
||||
// Start the Wire (I2C) library
|
||||
Wire.begin();
|
||||
|
||||
// Query the HamShield for status information
|
||||
Serial.print("Radio status: ");
|
||||
int result = radio.testConnection();
|
||||
@@ -52,9 +46,8 @@ void setup() {
|
||||
// Tell the HamShield to start up
|
||||
radio.initialize();
|
||||
radio.setRfPower(0);
|
||||
|
||||
// Configure the HamShield to transmit and recieve on 446.000MHz
|
||||
radio.frequency(438000);
|
||||
radio.frequency(145570);
|
||||
|
||||
Serial.println("Radio Configured.");
|
||||
}
|
||||
@@ -71,13 +64,13 @@ void loop() {
|
||||
radio.setModeTransmit();
|
||||
|
||||
// Send a message out in morse code
|
||||
radio.morseOut(" KC7IBT ARDUINO HAMSHIELD");
|
||||
radio.morseOut("KC7IBT ARDUINO HAMSHIELD");
|
||||
|
||||
// We're done sending the message, set the radio back into recieve mode.
|
||||
radio.setModeReceive();
|
||||
Serial.println("Done.");
|
||||
|
||||
// Wait a second before we send our beacon again.
|
||||
// Wait 30 seconds before we send our beacon again.
|
||||
delay(1000);
|
||||
} else {
|
||||
// If we get here, the channel is busy. Let's also print out the RSSI.
|
||||
|
||||
@@ -1,27 +1,19 @@
|
||||
/* Hamshield
|
||||
* Example: Fox Hunt
|
||||
* Plays a one minute tone at 10-13 minute intervals. Script
|
||||
* will check to see if the channel is clear before it will
|
||||
* transmit.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall power and then
|
||||
* to your computer via USB. To test, set a HandyTalkie
|
||||
* to 438MHz. You should hear a one-minute tone every 10-13 minutes.
|
||||
*/
|
||||
/* Fox Hunt */
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
#define SWITCH_PIN 2
|
||||
|
||||
// In milliseconds
|
||||
#define TRANSMITLENGTH 60000
|
||||
// In minutes
|
||||
// transmit for 1 minute, every 10 minutes
|
||||
|
||||
#define TRANSMITLENGTH 1
|
||||
#define INTERVAL 10
|
||||
#define RANDOMCHANCE 3
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
|
||||
void setup() {
|
||||
// NOTE: if not using PWM out, it should be held low to avoid tx noise
|
||||
@@ -35,24 +27,26 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
radio.initialize();
|
||||
radio.setRfPower(0);
|
||||
radio.frequency(438000);
|
||||
radio.setFrequency(145510);
|
||||
radio.setModeReceive();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if(radio.waitForChannel(30000,2000, -90)) { // wait for a clear channel, abort after 30 seconds, wait 2 seconds of dead air for breakers
|
||||
radio.setModeTransmit(); // turn on transmit mode
|
||||
tone(PWM_PIN, 1000, TRANSMITLENGTH); // play a long solid tone
|
||||
delay(TRANSMITLENGTH);
|
||||
radio.morseOut(" 1ZZ9ZZ/B FOXHUNT"); // identify the fox hunt transmitter
|
||||
radio.setModeReceive(); // turn off the transmit mode
|
||||
}
|
||||
waitMinute(INTERVAL + random(0,RANDOMCHANCE)); // wait before transmitting, randomly
|
||||
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
|
||||
radio.setModeTransmit(); // turn on transmit mode
|
||||
tone(1000,11,TRANSMITLENGTH * 60 * 1000); // play a long solid tone
|
||||
radio.morseOut("1ZZ9ZZ/B FOXHUNT"); // identify the fox hunt transmitter
|
||||
radio.setModeReceive(); // turn off the transmit mode
|
||||
}
|
||||
}
|
||||
|
||||
// a function so we can wait by minutes
|
||||
void waitMinute(unsigned long period) {
|
||||
|
||||
void waitMinute(int period) {
|
||||
delay(period * 60 * 1000);
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -1,18 +1,7 @@
|
||||
/* Hamshield
|
||||
* Example: Functional Test
|
||||
* This is a simple example to demonstrate HamShield receive
|
||||
* and transmit functionality.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then
|
||||
* to your computer via USB. After uploading this program to
|
||||
* your Arduino, open the Serial Monitor. Serial Monitor will
|
||||
* describe what you should be expecting to hear from your
|
||||
* headphones. Tune a HandytTalkie to 446MHz to hear morse
|
||||
* code example.
|
||||
*/
|
||||
/* HamShield Functional Test */
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -32,6 +21,7 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
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: ");
|
||||
@@ -44,7 +34,7 @@ void setup() {
|
||||
void loop() {
|
||||
radio.setModeReceive();
|
||||
radio.setSQLoThresh(0);
|
||||
radio.setSQOff();
|
||||
radio.setSQOn();
|
||||
radio.setVolume1(0xF);
|
||||
radio.setVolume2(0xF);
|
||||
delay(1000);
|
||||
|
||||
@@ -1,28 +1,27 @@
|
||||
/* Hamshield
|
||||
* Example: Gauges
|
||||
* This example prints Signal, Audio In, and Audio Rx ADC
|
||||
* Peak strength to the Serial Monitor in a graphical manner.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then
|
||||
* to your computer via USB. After uploading this program to
|
||||
* your Arduino, open the Serial Monitor. You will see a
|
||||
* repeating display of different signal strengths. Ex:
|
||||
*
|
||||
* [....|....] -73
|
||||
* Signal
|
||||
*
|
||||
* Uncheck the "Autoscroll" box at the bottom of the Serial
|
||||
* Monitor to manually control the view of the Serial Monitor.
|
||||
/*
|
||||
|
||||
Gauges
|
||||
|
||||
Simple gauges for the radio receiver.
|
||||
|
||||
|
||||
*/
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
#define SWITCH_PIN 2
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
|
||||
void clr() {
|
||||
/* Serial.write(27);
|
||||
Serial.print("[2J"); // cursor to home command */
|
||||
Serial.write(27);
|
||||
Serial.print("[H"); // cursor to home command
|
||||
}
|
||||
|
||||
void setup() {
|
||||
// NOTE: if not using PWM out, it should be held low to avoid tx noise
|
||||
@@ -37,13 +36,13 @@ void setup() {
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
analogReference(DEFAULT);
|
||||
Serial.begin(9600);
|
||||
|
||||
Serial.begin(115200);
|
||||
Wire.begin();
|
||||
Serial.print("Radio status: ");
|
||||
int result = radio.testConnection();
|
||||
Serial.println(result,DEC);
|
||||
radio.initialize();
|
||||
radio.frequency(446000);
|
||||
radio.setFrequency(446000);
|
||||
radio.setModeReceive();
|
||||
Serial.println("Entering gauges...");
|
||||
tone(9,1000);
|
||||
@@ -61,6 +60,7 @@ int txc = 0;
|
||||
int mode = 0;
|
||||
|
||||
void loop() {
|
||||
clr();
|
||||
int16_t rssi = radio.readRSSI();
|
||||
gauge = map(rssi,-123,-50,0,8);
|
||||
Serial.print("[");
|
||||
|
||||
23
examples/FixMe/HAMBot/HAMBot.ino → examples/HAMBot/HAMBot.ino
Normal file → Executable file
23
examples/FixMe/HAMBot/HAMBot.ino → examples/HAMBot/HAMBot.ino
Normal file → Executable file
@@ -1,28 +1,15 @@
|
||||
/* Hamshield
|
||||
* Example: HAMBot
|
||||
* Simple DTMF controlled HAM Radio Robot. You will need
|
||||
* seperate DTMF equipment as well as robot for this
|
||||
* example.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, you can send commands from
|
||||
* your DTMF equipment using the following list:
|
||||
* '4' => turn robot left
|
||||
* '6' => turn robot right
|
||||
* '2' => move robot forward
|
||||
* '5' => tell robot to send morse code identity
|
||||
*/
|
||||
/* Simple DTMF controlled HAM Radio Robot */
|
||||
|
||||
#include <ArduinoRobot.h> // include the robot library
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
#define SWITCH_PIN 2
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
|
||||
void setup() {
|
||||
// NOTE: if not using PWM out, it should be held low to avoid tx noise
|
||||
@@ -37,7 +24,7 @@ void setup() {
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Robot.begin();
|
||||
|
||||
Wire.begin();
|
||||
radio.initialize();
|
||||
radio.frequency(145510);
|
||||
}
|
||||
@@ -1,20 +1,8 @@
|
||||
/* Hamshield
|
||||
* Example: HandyTalkie
|
||||
* This is a simple example to demonstrate HamShield receive
|
||||
* and transmit functionality.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then
|
||||
* to your computer via USB. After uploading this program to
|
||||
* your Arduino, open the Serial Monitor. Press the button on
|
||||
* the HamShield to begin setup. After setup is complete, type
|
||||
* your desired Tx/Rx frequency, in hertz, into the bar at the
|
||||
* top of the Serial Monitor and click the "Send" button.
|
||||
* To test with another HandyTalkie (HT), key up on your HT
|
||||
* and make sure you can hear it through the headphones
|
||||
* attached to the HamShield. Key up on the HamShield by
|
||||
* holding the button.
|
||||
*/
|
||||
// Hamshield
|
||||
|
||||
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
|
||||
// is used in I2Cdev.h
|
||||
#include "Wire.h"
|
||||
|
||||
#include <HamShield.h>
|
||||
|
||||
@@ -60,6 +48,9 @@ void setup() {
|
||||
|
||||
Serial.println("beginning radio setup");
|
||||
|
||||
// join I2C bus (I2Cdev library doesn't do this automatically)
|
||||
Wire.begin();
|
||||
|
||||
// verify connection
|
||||
Serial.println("Testing device connections...");
|
||||
Serial.println(radio.testConnection() ? "RDA radio connection successful" : "RDA radio connection failed");
|
||||
|
||||
7
examples/FixMe/Identifier/Identifier.ino → examples/Identifier/Identifier.ino
Normal file → Executable file
7
examples/FixMe/Identifier/Identifier.ino → examples/Identifier/Identifier.ino
Normal file → Executable file
@@ -7,7 +7,8 @@ Arduino audio overlay example
|
||||
*/
|
||||
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define DOT 100
|
||||
|
||||
@@ -15,7 +16,7 @@ Arduino audio overlay example
|
||||
#define RESET_PIN A3
|
||||
#define SWITCH_PIN 2
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
|
||||
const char *bascii = "ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789.,?'!/()&:;=+-_\"$@",
|
||||
*bitu[] = { ".-","-...","-.-.","-..",".","..-.","--.","....","..",".---","-.-",".-..","--","-.","---",".--.","--.-",".-.","...","-","..-","...-",".--","-..-","-.--","--..","-----",".----","..---","...--","....-",".....","-....","--...","---..","----.",".-.-.-","--..--","..--..",".----.","-.-.--","-..-.","-.--.","-.--.-",".-...","---...","-.-.-.","-...-",".-.-.","-....-","..--.-",".-..-.","...-..-",".--.-."
|
||||
@@ -39,7 +40,7 @@ void setup() {
|
||||
|
||||
Serial.begin(9600);
|
||||
Serial.println("starting up..");
|
||||
|
||||
Wire.begin();
|
||||
Serial.print("Radio status: ");
|
||||
int result = radio.testConnection();
|
||||
Serial.println(result,DEC);
|
||||
@@ -1,17 +1,7 @@
|
||||
/* Hamshield
|
||||
* Example: Just Transmit
|
||||
* This example continuously transmits.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones with
|
||||
* built-in mic into the HamShield. Connect the Arduino to
|
||||
* wall power and then to your computer via USB. After
|
||||
* uploading this program to your Arduino, open the Serial
|
||||
* Monitor to monitor the program's progress. After setup is
|
||||
* complete, tune a HandyTalkie (HT) to 144.025MHz. Listen on
|
||||
* the HT for the HamShield broadcasting from the mic.
|
||||
*/
|
||||
/* Just Transmit */
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -31,6 +21,7 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
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: ");
|
||||
@@ -39,11 +30,12 @@ void setup() {
|
||||
Serial.println("Setting radio to its defaults..");
|
||||
radio.initialize();
|
||||
radio.setRfPower(0);
|
||||
radio.setChanMode(3);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
radio.bypassPreDeEmph();
|
||||
radio.frequency(144025);
|
||||
radio.frequency(144000);
|
||||
// radio.setTxSourceNone();
|
||||
radio.setModeTransmit();
|
||||
for(;;) { }
|
||||
|
||||
@@ -1,22 +1,10 @@
|
||||
/* Hamshield
|
||||
* Example: KISS
|
||||
* This is a example configures the HamShield to be used as
|
||||
* a TNC/KISS device. You will need a KISS device to input
|
||||
* commands to the HamShield
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. Issue commands
|
||||
* via the KISS equipment.
|
||||
*/
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <Wire.h>
|
||||
#include <KISS.h>
|
||||
#include <packet.h>
|
||||
|
||||
HamShield radio;
|
||||
DDS dds;
|
||||
KISS kiss(&Serial, &radio, &dds);
|
||||
AFSK afsk;
|
||||
|
||||
//TODO: move these into library
|
||||
#define PWM_PIN 3
|
||||
@@ -42,13 +30,14 @@ void setup() {
|
||||
// let the AU ot of reset
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
radio.initialize();
|
||||
radio.setSQOff();
|
||||
radio.frequency(144390);
|
||||
radio.setFrequency(144390);
|
||||
//I2Cdev::writeWord(A1846S_DEV_ADDR_SENLOW, 0x44, 0x05FF);
|
||||
|
||||
dds.start();
|
||||
afsk.start(&dds);
|
||||
radio.afsk.start(&dds);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
@@ -1,17 +1,4 @@
|
||||
/* Hamshield
|
||||
* Example: PSK31Transmit
|
||||
* This is a simple example to demonstrate HamShield PSK31
|
||||
* transmit functionality.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, tune a PSK31 receiver and
|
||||
* wait to receive the message "Why hello there, friend.
|
||||
* Nice to meet you. Welcome to PSK31. 73, VE6SLP sk"
|
||||
*/
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include "varicode.h"
|
||||
|
||||
#define PWM_PIN 3
|
||||
|
||||
35
examples/FixMe/Parrot/Parrot.ino → examples/Parrot/Parrot.ino
Normal file → Executable file
35
examples/FixMe/Parrot/Parrot.ino → examples/Parrot/Parrot.ino
Normal file → Executable file
@@ -1,19 +1,13 @@
|
||||
/* Hamshield
|
||||
* Example: Parrot
|
||||
* Record sound and then plays it back a few times. Very low
|
||||
* sound quality @ 2KHz 0.75 seconds. A bit robotic and weird.
|
||||
* You will need a HandyTalkie (HT) to test the output of this
|
||||
* example.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then to
|
||||
* your computer via USB. To test the output, tune you HT to
|
||||
* 446MHz. The HamShield should make a recording ofthe next
|
||||
* broadcast on that frequncy. The recording should then be
|
||||
* repeated ten times by the HamShield.
|
||||
/*
|
||||
|
||||
Record sound and then plays it back a few times.
|
||||
Very low sound quality @ 2KHz 0.75 seconds
|
||||
A bit robotic and weird
|
||||
|
||||
*/
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -22,7 +16,7 @@
|
||||
#define RATE 500
|
||||
#define SIZE 1500
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
|
||||
char sound[SIZE];
|
||||
unsigned int sample1;
|
||||
@@ -42,9 +36,10 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
// int result = radio.testConnection();
|
||||
radio.initialize();
|
||||
radio.frequency(446000);
|
||||
radio.setFrequency(446000);
|
||||
setPwmFrequency(9, 1);
|
||||
}
|
||||
|
||||
@@ -56,16 +51,16 @@ void loop() {
|
||||
if(x == -1) {
|
||||
for(x = 0; x < SIZE; x++) {
|
||||
if(mode == 4) {
|
||||
sample1 = analogRead(2);
|
||||
sample1 = analogRead(0);
|
||||
sound[x] = sample1 >> 4;
|
||||
delayMicroseconds(RATE); x++;
|
||||
sample1 = analogRead(2);
|
||||
sample1 = analogRead(0);
|
||||
sound[x] = (sample1 & 0xF0) | sound[x];
|
||||
delayMicroseconds(RATE);
|
||||
} else {
|
||||
sound[x] = analogRead(2);
|
||||
sound[x] = analogRead(0);
|
||||
delayMicroseconds(RATE); x++;
|
||||
sound[x] = analogRead(2);
|
||||
sound[x] = analogRead(0);
|
||||
delayMicroseconds(RATE);
|
||||
}
|
||||
}
|
||||
@@ -1,17 +1,4 @@
|
||||
/* Hamshield
|
||||
* Example: QPSK63Transmit
|
||||
* This is a simple example to demonstrate HamShield QPSK63
|
||||
* transmit functionality.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, tune a QPSK63 receiver and
|
||||
* wait to receive the message "Why hello there, friend.
|
||||
* Nice to meet you. Welcome to QPSK63. 73, VE6SLP sk"
|
||||
*/
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include "varicode.h"
|
||||
|
||||
#define PWM_PIN 3
|
||||
@@ -59,7 +46,7 @@ void sendChar(uint8_t c) {
|
||||
//PORTD &= ~_BV(2); // Diagnostic pin (D2)
|
||||
}
|
||||
|
||||
char *string = "Why hello there, friend. Nice to meet you. Welcome to QPSK63. 73, VE6SLP sk\r\n";
|
||||
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:
|
||||
|
||||
@@ -1,13 +1,7 @@
|
||||
/* Hamshield
|
||||
* Example: SSTV
|
||||
* This program will transmit a test pattern. You will need
|
||||
* SSTV equipment to test the output.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, open the Serial Monitor to
|
||||
* view the status of the program. Tune your SSTV to
|
||||
* 446MHz to receive the image output.
|
||||
/*
|
||||
|
||||
Sends an SSTV test pattern
|
||||
|
||||
*/
|
||||
|
||||
#define PWM_PIN 3
|
||||
@@ -19,9 +13,10 @@
|
||||
|
||||
/* Standard libraries and variable init */
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
int16_t rssi;
|
||||
|
||||
/* get our radio ready */
|
||||
@@ -38,6 +33,7 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
Serial.begin(9600);
|
||||
Serial.print("Radio status: ");
|
||||
int result = radio.testConnection();
|
||||
@@ -51,7 +47,7 @@ void setup() {
|
||||
|
||||
|
||||
void loop() {
|
||||
if(radio.waitForChannel(1000,2000, -90)) { // Wait forever for calling frequency to open, then wait 2 seconds for breakers
|
||||
if(radio.waitForChannel(1000,2000)) { // Wait forever for calling frequency to open, then wait 2 seconds for breakers
|
||||
radio.setModeTransmit(); // Turn on the transmitter
|
||||
delay(250); // Wait a moment
|
||||
radio.SSTVTestPattern(MARTIN1); // send a MARTIN1 test pattern
|
||||
|
||||
@@ -1,20 +1,8 @@
|
||||
/* Hamshield
|
||||
* Example: SSTV M1 Static
|
||||
* This program will transmit a static image. You will need
|
||||
* SSTV equipment to test the output.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Connect the Arduino to wall
|
||||
* power and then to your computer via USB. After uploading
|
||||
* this program to your Arduino, open the Serial Monitor to
|
||||
* view the status of the program. Tune your SSTV to
|
||||
* 145.5MHz to receive the image output.
|
||||
*/
|
||||
|
||||
// So the precalculated values will get stored
|
||||
#define DDS_REFCLK_DEFAULT (34965/2)
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <DDS.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
@@ -43,8 +31,8 @@ void setup() {
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Serial.begin(9600);
|
||||
|
||||
// Query the HamShield for status information
|
||||
Wire.begin();
|
||||
// Query the HamShield for status information
|
||||
Serial.print("Radio status: ");
|
||||
int result = 0;
|
||||
result = radio.testConnection();
|
||||
|
||||
@@ -1,19 +1,6 @@
|
||||
/* Hamshield
|
||||
* Example: Serial Tranceiver
|
||||
* SerialTransceiver is TTL Serial port "glue" to allow
|
||||
* desktop or laptop control of the HamShield.
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then
|
||||
* to your computer via USB. After uploading this program to
|
||||
* your Arduino, open the Serial Monitor. Use the bar at the
|
||||
* top of the serial monitor to enter commands as seen below.
|
||||
*
|
||||
* EXAMPLE: To change the repeater offset to 144.425MHz,
|
||||
* enable offset, then key in, use the following commands:
|
||||
* T144425;
|
||||
* R1;
|
||||
* [Just a space]
|
||||
/*
|
||||
|
||||
SerialTransceiver is TTL Serial port "glue" to allow desktop or laptop control of the HAMShield
|
||||
|
||||
Commands:
|
||||
|
||||
@@ -59,6 +46,7 @@ Debug Msg @<text>; 32 character debug message
|
||||
|
||||
*/
|
||||
|
||||
#include "Wire.h"
|
||||
#include "HamShield.h"
|
||||
|
||||
#define PWM_PIN 3
|
||||
@@ -95,15 +83,15 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Serial.begin(9600);
|
||||
Serial.println(";;;;;;;;;;;;;;;;;;;;;;;;;;");
|
||||
|
||||
Serial.begin(115200);
|
||||
Serial.print(";;;;;;;;;;;;;;;;;;;;;;;;;;");
|
||||
Wire.begin();
|
||||
int result = radio.testConnection();
|
||||
Serial.print("*");
|
||||
Serial.print(result,DEC);
|
||||
Serial.println(";");
|
||||
Serial.print(";");
|
||||
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
|
||||
Serial.println("*START;");
|
||||
Serial.print("*START;");
|
||||
radio.frequency(freq);
|
||||
radio.setVolume1(0xF);
|
||||
radio.setVolume2(0xF);
|
||||
@@ -133,14 +121,14 @@ void loop() {
|
||||
if(repeater == 1) { radio.frequency(tx); }
|
||||
radio.setModeTransmit();
|
||||
state = 10;
|
||||
Serial.println("#TX,ON;");
|
||||
Serial.print("#TX,ON;");
|
||||
timer = millis();
|
||||
break;
|
||||
|
||||
case 63: // ? - RSSI
|
||||
Serial.print(":");
|
||||
Serial.print(radio.readRSSI(),DEC);
|
||||
Serial.println(";");
|
||||
Serial.print(";");
|
||||
break;
|
||||
|
||||
case 65: // A - CTCSS In
|
||||
@@ -161,7 +149,7 @@ void loop() {
|
||||
case 70: // F - frequency
|
||||
getValue();
|
||||
freq = atol(cmdbuff);
|
||||
if(radio.frequency(freq) == true) { Serial.print("@"); Serial.print(freq,DEC); Serial.println(";!;"); } else { Serial.println("X1;"); }
|
||||
if(radio.frequency(freq) == true) { Serial.print("@"); Serial.print(freq,DEC); Serial.print(";!;"); } else { Serial.print("X1;"); }
|
||||
break;
|
||||
|
||||
case 'M':
|
||||
@@ -200,14 +188,14 @@ void loop() {
|
||||
case 94: // ^ - VSSI (voice) level
|
||||
Serial.print(":");
|
||||
Serial.print(radio.readVSSI(),DEC);
|
||||
Serial.println(";");
|
||||
Serial.print(";");
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
if(state == 10) {
|
||||
if(millis() > (timer + 500)) { Serial.println("#TX,OFF;");radio.setModeReceive(); 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; }
|
||||
}
|
||||
}
|
||||
|
||||
@@ -218,8 +206,7 @@ void getValue() {
|
||||
if(Serial.available()) {
|
||||
temp = Serial.read();
|
||||
if(temp == 59) { cmdbuff[p] = 0; Serial.print("@");
|
||||
for(int x = 0; x < 32; x++) { Serial.print(cmdbuff[x]);}
|
||||
Serial.println();
|
||||
for(int x = 0; x < 32; x++) { Serial.print(cmdbuff[x]); }
|
||||
return;
|
||||
}
|
||||
cmdbuff[p] = temp;
|
||||
@@ -227,12 +214,12 @@ void getValue() {
|
||||
if(p == 32) {
|
||||
Serial.print("@");
|
||||
for(int x = 0; x < 32; x++) {
|
||||
Serial.println(cmdbuff[x]);
|
||||
Serial.print(cmdbuff[x]);
|
||||
}
|
||||
|
||||
cmdbuff[0] = 0;
|
||||
|
||||
Serial.println("X0;"); return; } // some sort of alignment issue? lets not feed junk into whatever takes this string in
|
||||
Serial.print("X0;"); return; } // some sort of alignment issue? lets not feed junk into whatever takes this string in
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,35 +1,24 @@
|
||||
/* Hamshield
|
||||
* Example: Signal Test
|
||||
* Plays back the current signal strength level and morses out
|
||||
* it's call sign at the end. You will need a HandyTalkie (HT)
|
||||
* to test the output of this example. You will also need to
|
||||
* download the PCM library from
|
||||
* https://github.com/damellis/PCM
|
||||
* Connect the HamShield to your Arduino. Screw the antenna
|
||||
* into the HamShield RF jack. Plug a pair of headphones into
|
||||
* the HamShield. Connect the Arduino to wall power and then
|
||||
* to your computer via USB. After uploading this program to
|
||||
* your Arduino, open the Serial Monitor. HamShield will print
|
||||
* the results of its signal test to the Serial Monitor. To
|
||||
* test with another HandyTalkie (HT), tune in to 446MHz and
|
||||
* listen for the call sign. Then key up on your HT and make
|
||||
* sure you can hear it through the headphones attached to the
|
||||
* HamShield.
|
||||
/*
|
||||
|
||||
Plays back the current signal strength level and morses out it's call sign at the end.
|
||||
|
||||
|
||||
*/
|
||||
|
||||
#define DOT 100
|
||||
char CALLSIGN[] = "1ZZ9ZZ/B";
|
||||
#define CALLSIGN "1ZZ9ZZ/B"
|
||||
|
||||
/* Standard libraries and variable init */
|
||||
|
||||
#include <HamShield.h>
|
||||
#include <HAMShield.h>
|
||||
#include <Wire.h>
|
||||
#include <PCM.h>
|
||||
|
||||
#define PWM_PIN 3
|
||||
#define RESET_PIN A3
|
||||
#define SWITCH_PIN 2
|
||||
|
||||
HamShield radio;
|
||||
HAMShield radio;
|
||||
int16_t rssi;
|
||||
int peak = -150;
|
||||
char sig[8];
|
||||
@@ -100,6 +89,7 @@ void setup() {
|
||||
pinMode(RESET_PIN, OUTPUT);
|
||||
digitalWrite(RESET_PIN, HIGH);
|
||||
|
||||
Wire.begin();
|
||||
Serial.begin(9600);
|
||||
Serial.print("Radio status: ");
|
||||
int result = radio.testConnection();
|
||||
|
||||
@@ -1,10 +0,0 @@
|
||||
name=HamShield
|
||||
version=1.0.2
|
||||
author=Morgan Redfield <morgan@enhancedradio.com>, Casey Halverson <casey@enhancedradio.com>
|
||||
maintainer=Morgan Redfield <morgan@enhancedradio.com>
|
||||
sentence=A library for use with HamShield by Enhanced Radio Devices.
|
||||
paragraph=
|
||||
category=Device Control
|
||||
url=http://www.hamshield.com
|
||||
architectures=*
|
||||
includes=HamShield.h
|
||||
@@ -1,114 +0,0 @@
|
||||
/*
|
||||
* 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;
|
||||
pinMode(DAT, OUTPUT);
|
||||
regAddr = regAddr | (1 << 7);
|
||||
|
||||
digitalWrite(devAddr, 0); //PORTC &= ~(1<<1); //devAddr used as chip select
|
||||
for (int i = 0; i < 8; i++) {
|
||||
temp = ((regAddr & (0x80 >> i)) != 0);
|
||||
digitalWrite(CLK, 0); //PORTC &= ~(1<<5); //
|
||||
digitalWrite(DAT, temp);
|
||||
digitalWrite(CLK, 1); //PORTC |= (1<<5); //
|
||||
}
|
||||
// change direction of DAT
|
||||
pinMode(DAT, INPUT); // DDRC &= ~(1<<4); //
|
||||
for (int i = 15; i >= 0; i--) {
|
||||
digitalWrite(CLK, 0); //PORTC &= ~(1<<5); //
|
||||
digitalWrite(CLK, 1); //PORTC |= (1<<5); //
|
||||
temp_dat = digitalRead(DAT); //((PINC & (1<<4)) != 0);
|
||||
temp_dat = temp_dat << i;
|
||||
*data |= temp_dat;
|
||||
}
|
||||
digitalWrite(devAddr, 1); //PORTC |= (1<<1);// CS
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool HSwriteBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data)
|
||||
{
|
||||
uint16_t w;
|
||||
HSreadWord(devAddr, regAddr, &w);
|
||||
w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum));
|
||||
return HSwriteWord(devAddr, regAddr, w);
|
||||
}
|
||||
|
||||
bool HSwriteBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data)
|
||||
{
|
||||
uint16_t w;
|
||||
if (HSreadWord(devAddr, regAddr, &w) != 0) {
|
||||
uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
|
||||
data <<= (bitStart - length + 1); // shift data into correct position
|
||||
data &= mask; // zero all non-important bits in data
|
||||
w &= ~(mask); // zero all important bits in existing word
|
||||
w |= data; // combine data with existing word
|
||||
return HSwriteWord(devAddr, regAddr, w);
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool HSwriteWord(uint8_t devAddr, uint8_t regAddr, uint16_t data)
|
||||
{
|
||||
//return I2Cdev::writeWord(devAddr, regAddr, data);
|
||||
|
||||
uint8_t temp_reg;
|
||||
uint16_t temp_dat;
|
||||
|
||||
//digitalWrite(13, HIGH);
|
||||
|
||||
// bitbang for great justice!
|
||||
pinMode(DAT, OUTPUT);
|
||||
regAddr = regAddr & ~(1 << 7);
|
||||
|
||||
digitalWrite(devAddr, 0); // PORTC &= ~(1<<1); //CS
|
||||
for (int i = 0; i < 8; i++) {
|
||||
temp_reg = ((regAddr & (0x80 >> i)) != 0);
|
||||
digitalWrite(CLK, 0); //PORTC &= ~(1<<5); //
|
||||
digitalWrite(DAT, regAddr & (0x80 >> i));
|
||||
digitalWrite(CLK, 1); // PORTC |= (1<<5); //
|
||||
}
|
||||
for (int i = 0; i < 16; i++) {
|
||||
temp_dat = ((data & (0x8000 >> i)) != 0);
|
||||
digitalWrite(CLK, 0); //PORTC &= ~(1<<5); //
|
||||
digitalWrite(DAT, temp_dat);
|
||||
digitalWrite(CLK, 1); // PORTC |= (1<<5); //
|
||||
}
|
||||
|
||||
digitalWrite(devAddr, 1); //PORTC |= (1<<1); //CS
|
||||
|
||||
return true;
|
||||
}
|
||||
@@ -1,22 +0,0 @@
|
||||
|
||||
|
||||
|
||||
#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_ */
|
||||
Reference in New Issue
Block a user