Compare commits

..

No commits in common. "master" and "1.1.1" have entirely different histories.

23 changed files with 797 additions and 2318 deletions

View File

@ -1,7 +1,5 @@
# HamShield # HamShield
You can purchase HamShield (as well as smaller variants or LoRa version) at http://www.enhancedradio.com/
The master branch is intended for use with HamShield hardware -09 and above. The master branch is intended for use with HamShield hardware -09 and above.
WARNING: The dev branch is not guaranteed to work. Please use caution if you choose to use that branch. WARNING: The dev branch is not guaranteed to work. Please use caution if you choose to use that branch.

View File

@ -12,7 +12,7 @@
* To send a message: connect to the Arduino over a Serial link. * To send a message: connect to the Arduino over a Serial link.
* Send the following over the serial link: * Send the following over the serial link:
* `from,to,:message * `from,to,:message
* example: * KG7OGM,KG7OGM,:Hi there` * example: * `KG7OGM,KG7OGM,:Hi there
*/ */
@ -22,7 +22,7 @@
#include <packet.h> #include <packet.h>
#include <avr/wdt.h> #include <avr/wdt.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -37,11 +37,10 @@ int msgptr = 0;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
@ -53,14 +52,14 @@ void setup() {
Serial.begin(9600); Serial.begin(9600);
radio.initialize(); radio.initialize();
radio.frequency(144390); // default aprs frequency in North America radio.frequency(145570);
radio.setRfPower(0); radio.setRfPower(0);
radio.setVolume1(0xFF); radio.setVolume1(0xFF);
radio.setVolume2(0xFF); radio.setVolume2(0xFF);
radio.setSQHiThresh(-100); radio.setSQHiThresh(-100);
radio.setSQLoThresh(-100); radio.setSQLoThresh(-100);
//radio.setSQOn(); radio.setSQOn();
radio.bypassPreDeEmph(); //radio.bypassPreDeEmph();
dds.start(); dds.start();
afsk.start(&dds); afsk.start(&dds);
delay(100); delay(100);
@ -75,7 +74,6 @@ void loop() {
//Serial.println(messagebuff); //Serial.println(messagebuff);
prepMessage(); prepMessage();
msgptr = 0; msgptr = 0;
messagebuff = "";
Serial.print("!!"); Serial.print("!!");
} }
else { else {

View File

@ -5,7 +5,7 @@
#include <HamShield.h> #include <HamShield.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -17,14 +17,13 @@ uint8_t pl_rx_buffer[32];
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -37,7 +36,7 @@ void setup() {
Serial.println("Setting radio to its defaults.."); Serial.println("Setting radio to its defaults..");
radio.initialize(); radio.initialize();
radio.setRfPower(0); radio.setRfPower(0);
radio.frequency(432100); // 70cm calling frequency radio.frequency(146520);
radio.setModeReceive(); radio.setModeReceive();
} }

View File

@ -29,7 +29,7 @@ HamShield radio;
#define LED_PIN 13 #define LED_PIN 13
#define RSSI_REPORT_RATE_MS 5000 #define RSSI_REPORT_RATE_MS 5000
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -43,14 +43,13 @@ unsigned long rssi_timeout;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW); digitalWrite(RESET_PIN, LOW);
@ -69,18 +68,20 @@ void setup() {
// verify connection // verify connection
Serial.println("Testing device connections..."); Serial.println("Testing device connections...");
Serial.println(radio.testConnection() ? "radio connection successful" : "radio connection failed"); Serial.println(radio.testConnection() ? "RDA radio connection successful" : "RDA radio connection failed");
// initialize device // initialize device
Serial.println("Initializing radio device..."); Serial.println("Initializing I2C devices...");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration"); Serial.println("setting default Radio configuration");
radio.dangerMode();
// set frequency // set frequency
Serial.println("changing frequency"); Serial.println("changing frequency");
freq = 432100; // 70cm calling frequency radio.setSQOff();
freq = 446000;
radio.frequency(freq); radio.frequency(freq);
// set to receive // set to receive
@ -91,11 +92,6 @@ void setup() {
Serial.println(radio.readCtlReg()); Serial.println(radio.readCtlReg());
Serial.println(radio.readRSSI()); Serial.println(radio.readRSSI());
// set up squelch
radio.setSQLoThresh(-80);
radio.setSQHiThresh(-70);
radio.setSQOn();
radio.setRfPower(0); radio.setRfPower(0);
// CTCSS Setup code // CTCSS Setup code
@ -167,7 +163,7 @@ void loop() {
} else { } else {
Serial.setTimeout(40); Serial.setTimeout(40);
freq = Serial.parseInt(); freq = Serial.parseInt();
while (Serial.available()) Serial.read(); Serial.flush();
radio.frequency(freq); radio.frequency(freq);
Serial.print("set frequency: "); Serial.print("set frequency: ");
Serial.println(freq); Serial.println(freq);

View File

@ -14,7 +14,7 @@
#include <HamShield.h> #include <HamShield.h>
#include <DDS.h> #include <DDS.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -26,14 +26,13 @@ DDS dds;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
// turn on radio // turn on radio
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);

View File

@ -1,12 +1,12 @@
/* Hamshield /* Hamshield
* Example: DTMF * Example: DTMF
* This is a simple example to demonstrate how to use DTMF. * This is a simple example to demonstrate how to ues DTMF.
* *
* Connect the HamShield to your Arduino. Screw the antenna * Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. * into the HamShield RF jack.
* Connect the Arduino to wall power and then to your computer * Connect the Arduino to wall power and then to your computer
* via USB. After uploading this program to your Arduino, open * via USB. After uploading this program to your Arduino, open
* the Serial Monitor. Press the switch on the HamShield to * the Serial Monitor. Press the button on the HamShield to
* begin setup. After setup is complete, type in a DTMF value * begin setup. After setup is complete, type in a DTMF value
* (0-9, A, B, C, D, *, #) and hit enter. The corresponding * (0-9, A, B, C, D, *, #) and hit enter. The corresponding
* DTMF tones will be transmitted. The sketch will also print * DTMF tones will be transmitted. The sketch will also print
@ -20,7 +20,7 @@ HamShield radio;
#define LED_PIN 13 #define LED_PIN 13
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -28,14 +28,13 @@ uint32_t freq;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW); digitalWrite(RESET_PIN, LOW);
@ -46,7 +45,7 @@ void setup() {
while (digitalRead(SWITCH_PIN)); while (digitalRead(SWITCH_PIN));
// now we let the AU ot of reset // let the AU ot of reset
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -57,7 +56,7 @@ void setup() {
Serial.println(radio.testConnection() ? "HamShield connection successful" : "HamShield connection failed"); Serial.println(radio.testConnection() ? "HamShield connection successful" : "HamShield connection failed");
// initialize device // initialize device
radio.initialize(); radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration"); Serial.println("setting default Radio configuration");
@ -72,11 +71,11 @@ void setup() {
radio.setSQOn(); radio.setSQOn();
//radio.setSQOff(); //radio.setSQOff();
Serial.println("setting frequency to: "); Serial.println("changing frequency");
freq = 432100; // 70cm calling frequency freq = 420000;
radio.frequency(freq); radio.frequency(freq);
Serial.print(radio.getFrequency()); Serial.print("new frequency: ");
Serial.println("kHz"); Serial.println(radio.getFrequency());
// set RX volume to minimum to reduce false positives on DTMF rx // set RX volume to minimum to reduce false positives on DTMF rx
radio.setVolume1(6); radio.setVolume1(6);
@ -105,18 +104,33 @@ void setup() {
Serial.println("ready"); Serial.println("ready");
} }
char rx_dtmf_buf[255];
int rx_dtmf_idx = 0;
void loop() { void loop() {
// look for tone // look for tone
char m = radio.DTMFRxLoop(); if (radio.getDTMFSample() != 0) {
if (m != 0) { uint16_t code = radio.getDTMFCode();
Serial.print(m);
rx_dtmf_buf[rx_dtmf_idx++] = code2char(code);
// reset after this tone
int j = 0;
while (j < 4) {
if (radio.getDTMFSample() == 0) {
j++;
}
delay(10);
}
} else if (rx_dtmf_idx > 0) {
rx_dtmf_buf[rx_dtmf_idx] = '\0'; // NULL terminate the string
Serial.println(rx_dtmf_buf);
rx_dtmf_idx = 0;
} }
// Is it time to send tone? // Is it time to send tone?
if (Serial.available()) { if (Serial.available()) {
// get first code uint8_t code = char2code(Serial.read());
uint8_t code = radio.DTMFchar2code(Serial.read());
// start transmitting // start transmitting
radio.setDTMFCode(code); // set first radio.setDTMFCode(code); // set first
@ -131,23 +145,56 @@ void loop() {
// wait until we're ready for a new code // wait until we're ready for a new code
delay(10); delay(10);
} }
if (Serial.available()) {
code = radio.DTMFchar2code(Serial.read());
if (code == 255) code = 0xE; // throw a * in there so we don't break things with an invalid code
radio.setDTMFCode(code); // set first
} else {
dtmf_to_tx = false;
break;
}
while (radio.getDTMFTxActive() != 0) { while (radio.getDTMFTxActive() != 0) {
// wait until this code is done // wait until this code is done
delay(10); delay(10);
} }
if (Serial.available()) {
code = char2code(Serial.read());
if (code == 255) code = 0xE; // throw a * in there so we don't break things with an invalid code
radio.setDTMFCode(code); // set first
} else {
dtmf_to_tx = false;
}
} }
// done with tone // done with tone
radio.setModeReceive(); radio.setModeReceive();
radio.setTxSourceMic(); radio.setTxSourceMic();
} }
} }
uint8_t char2code(char c) {
uint8_t code;
if (c == '#') {
code = 0xF;
} else if (c=='*') {
code = 0xE;
} else if (c >= 'A' && c <= 'D') {
code = c - 'A' + 0xA;
} else if (c >= '0' && c <= '9') {
code = c - '0';
} else {
// invalid code, skip it
code = 255;
}
return code;
}
char code2char(uint16_t code) {
char c;
if (code < 10) {
c = '0' + code;
} else if (code < 0xE) {
c = 'A' + code - 10;
} else if (code == 0xE) {
c = '*';
} else if (code == 0xF) {
c = '#';
} else {
c = '?'; // invalid code
}
return c;
}

View File

@ -16,7 +16,7 @@
#define DDS_REFCLK_DEFAULT 9600 #define DDS_REFCLK_DEFAULT 9600
#include <HamShield.h> #include <HamShield.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -25,14 +25,13 @@ HamShield radio;
// Run our start up things here // Run our start up things here
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -58,8 +57,8 @@ void setup() {
radio.setMorseFreq(600); radio.setMorseFreq(600);
radio.setMorseDotMillis(100); radio.setMorseDotMillis(100);
// Configure the HamShield // Configure the HamShield to operate on 438.000MHz
radio.frequency(432300); // 70cm beacon frequency radio.frequency(438000);
Serial.println("Radio Configured."); Serial.println("Radio Configured.");
} }

View File

@ -15,7 +15,7 @@
#include <HamShield.h> #include <HamShield.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -29,14 +29,13 @@ HamShield radio;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -62,8 +61,8 @@ void setup() {
radio.setMorseFreq(600); radio.setMorseFreq(600);
radio.setMorseDotMillis(100); radio.setMorseDotMillis(100);
// Configure the HamShield frequency // Configure the HamShield to operate on 438.000Mhz
radio.frequency(432400); radio.frequency(438000);
Serial.println("Radio configured."); Serial.println("Radio configured.");
} }
@ -80,7 +79,7 @@ void loop() {
radio.setModeTransmit(); radio.setModeTransmit();
// Generate a 600Hz tone for TRANSMITLENGTH time // Generate a 600Hz tone for TRANSMITLENGTH time
tone(MIC_PIN, 600, TRANSMITLENGTH); tone(PWM_PIN, 600, TRANSMITLENGTH);
delay(TRANSMITLENGTH); delay(TRANSMITLENGTH);
// Identify the transmitter // Identify the transmitter

View File

@ -20,13 +20,11 @@
// create object for radio // create object for radio
HamShield radio; HamShield radio;
// To use non-standard pins, use the following initialization
//HamShield radio(ncs_pin, clk_pin, dat_pin);
#define LED_PIN 13 #define LED_PIN 13
#define RSSI_REPORT_RATE_MS 5000 #define RSSI_REPORT_RATE_MS 5000
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -39,27 +37,24 @@ unsigned long rssi_timeout;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, LOW); digitalWrite(RESET_PIN, LOW);
// initialize serial communication // initialize serial communication
Serial.begin(9600); Serial.begin(9600);
Serial.println("press the switch or send any character to begin..."); Serial.println("press the switch to begin...");
while (digitalRead(SWITCH_PIN) && !Serial.available()); while (digitalRead(SWITCH_PIN));
Serial.read(); // flush
// let the radio out of reset // let the AU ot of reset
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -67,19 +62,20 @@ void setup() {
// verify connection // verify connection
Serial.println("Testing device connections..."); Serial.println("Testing device connections...");
Serial.println(radio.testConnection() ? "radio connection successful" : "radio connection failed"); Serial.println(radio.testConnection() ? "RDA radio connection successful" : "RDA radio connection failed");
// initialize device // initialize device
Serial.println("Initializing radio device..."); Serial.println("Initializing I2C devices...");
radio.initialize(); // initializes automatically for UHF 12.5kHz channel radio.initialize(); // initializes automatically for UHF 12.5kHz channel
Serial.println("setting default Radio configuration"); Serial.println("setting default Radio configuration");
radio.dangerMode();
// set frequency // set frequency
Serial.println("changing frequency"); Serial.println("changing frequency");
radio.setSQOff(); radio.setSQOff();
freq = 432100; // 70cm calling frequency freq = 446000;
radio.frequency(freq); radio.frequency(freq);
// set to receive // set to receive
@ -137,7 +133,7 @@ void loop() {
} else { } else {
Serial.setTimeout(40); Serial.setTimeout(40);
freq = Serial.parseInt(); freq = Serial.parseInt();
while (Serial.available()) Serial.read(); Serial.flush();
radio.frequency(freq); radio.frequency(freq);
Serial.print("set frequency: "); Serial.print("set frequency: ");
Serial.println(freq); Serial.println(freq);

View File

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

View File

@ -8,11 +8,6 @@
* power and then to your computer via USB. Issue commands * power and then to your computer via USB. Issue commands
* via the KISS equipment. * via the KISS equipment.
* *
* You can also just use the serial terminal to send and receive
* APRS packets, but keep in mind that several fields in the packet
* are bit-shifted from standard ASCII (so if you're receiving,
* you won't get human readable callsigns or paths).
*
* To use the KISS example with YAAC: * To use the KISS example with YAAC:
* 1. open the configure YAAC wizard * 1. open the configure YAAC wizard
* 2. follow the prompts and enter in your details until you get to the "Add and Configure Interfaces" window * 2. follow the prompts and enter in your details until you get to the "Add and Configure Interfaces" window
@ -35,20 +30,19 @@ DDS dds;
AFSK afsk; AFSK afsk;
KISS kiss(&Serial, &radio, &dds, &afsk); KISS kiss(&Serial, &radio, &dds, &afsk);
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -61,9 +55,9 @@ void setup() {
radio.setVolume2(0xFF); radio.setVolume2(0xFF);
radio.setSQHiThresh(-100); radio.setSQHiThresh(-100);
radio.setSQLoThresh(-100); radio.setSQLoThresh(-100);
//radio.setSQOn(); radio.setSQOn();
radio.frequency(144390); radio.frequency(144390);
radio.bypassPreDeEmph(); //radio.bypassPreDeEmph();
dds.start(); dds.start();
afsk.start(&dds); afsk.start(&dds);

View File

@ -10,46 +10,51 @@
* monitor the status of the beacon. To test, set a HandyTalkie * monitor the status of the beacon. To test, set a HandyTalkie
* to 438MHz. You should hear the message " CALLSIGN HAMSHIELD" * to 438MHz. You should hear the message " CALLSIGN HAMSHIELD"
* in morse code. * in morse code.
*
*
* Note: only upper case letters, numbers, and a few symbols
* are supported.
* Supported symbols: &/+(=:?";@`-._),!$
*
* If you're having trouble accurately decoding, you may want to
* tweak the min/max . and - times. You can also uncomment
* the Serial.print debug statements that can tell you when tones
* are being detected, how long they're detected for, and whether
* the tones are decoded as a . or -.
*
*/ */
#define DDS_REFCLK_DEFAULT 9600 #define DDS_REFCLK_DEFAULT 9600
#include <HamShield.h> #include <HamShield.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
#define MORSE_FREQ 600 #define MORSE_FREQ 600
#define MORSE_DOT 150 // ms #define MORSE_DOT 100 // ms
// Note that all timing is defined in terms of MORSE_DOT relative durations // Note that all timing is defined in terms of MORSE_DOT relative durations
// You may want to tweak those timings below // You may want to tweak those timings below
#define SYMBOL_END_TIME 5 //millis
#define CHAR_END_TIME (MORSE_DOT*2.3)
#define MESSAGE_END_TIME (MORSE_DOT*15)
#define MIN_DOT_TIME (MORSE_DOT*0.7)
#define MAX_DOT_TIME (MORSE_DOT*1.3)
#define MIN_DASH_TIME (MORSE_DOT*2.7)
#define MAX_DASH_TIME (MORSE_DOT*3.3)
HamShield radio; HamShield radio;
uint32_t last_tone_check; // track how often we check for morse tones
uint32_t tone_in_progress; // track how long the current tone lasts
uint32_t space_in_progress; // track how long since the last tone
uint8_t rx_morse_char;
uint8_t rx_morse_bit;
char rx_msg[128];
uint8_t rx_idx;
// Run our start up things here // Run our start up things here
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -75,19 +80,63 @@ void setup() {
radio.setMorseDotMillis(MORSE_DOT); radio.setMorseDotMillis(MORSE_DOT);
radio.lookForTone(MORSE_FREQ); radio.lookForTone(MORSE_FREQ);
radio.setupMorseRx();
// Configure the HamShield frequency // Configure the HamShield to operate on 438.000MHz
radio.frequency(432100); // 70cm calling frequency radio.frequency((uint32_t) 438000);
radio.setModeReceive(); radio.setModeReceive();
Serial.println("Radio Configured."); Serial.println("Radio Configured.");
last_tone_check = millis();
space_in_progress = 0; // haven't checked yet
tone_in_progress = 0; // not currently listening to a tone
rx_morse_char = 0; // haven't found any tones yet
rx_idx = 0;
rx_morse_bit = 1;
} }
void loop() { void loop() {
char rx_char = radio.morseRxLoop(); // are we receiving anything
if (rx_char != 0) { if (radio.toneDetected()) {
Serial.print(rx_char); space_in_progress = 0;
if (tone_in_progress == 0) {
// start a new tone
tone_in_progress = millis();
}
} else {
// keep track of how long the silence is
if (space_in_progress == 0) space_in_progress = millis();
// we wait for a bit of silence before ending the last
// symbol in order to smooth out the detector
if ((millis() - space_in_progress) > SYMBOL_END_TIME)
{
if (tone_in_progress != 0) {
// end the last tone
uint16_t tone_time = millis() - tone_in_progress;
tone_in_progress = 0;
handleTone(tone_time);
}
}
// we might be done with a character if the space is long enough
if ((millis() - space_in_progress) > CHAR_END_TIME) {
char m = parseMorse();
if (m != 0) {
rx_msg[rx_idx++] = m;
}
}
// we might be done with a message if the space is long enough
if ((millis() - space_in_progress) > MESSAGE_END_TIME) {
if (rx_idx > 0) {
// we got a message, print it now
rx_msg[rx_idx] = '\0'; // null terminate
Serial.println(rx_msg);
rx_idx = 0; // reset message buffer
}
rx_morse_char = 0;
rx_morse_bit = 1;
}
} }
// should we send anything // should we send anything
@ -96,11 +145,9 @@ void loop() {
// We'll wait up to 30 seconds for a clear channel, requiring that the channel is clear for 2 seconds before we transmit // We'll wait up to 30 seconds for a clear channel, requiring that the channel is clear for 2 seconds before we transmit
if (radio.waitForChannel(30000,2000,-5)) { if (radio.waitForChannel(30000,2000,-5)) {
// If we get here, the channel is clear. // If we get here, the channel is clear.
Serial.println("sending");
// Start transmitting by putting the radio into transmit mode. // Start transmitting by putting the radio into transmit mode.
radio.setModeTransmit(); radio.setModeTransmit();
Serial.println("tx");
unsigned int MORSE_BUF_SIZE = 128; unsigned int MORSE_BUF_SIZE = 128;
char morse_buf[MORSE_BUF_SIZE]; char morse_buf[MORSE_BUF_SIZE];
unsigned int morse_idx; unsigned int morse_idx;
@ -114,9 +161,8 @@ void loop() {
radio.morseOut(morse_buf); radio.morseOut(morse_buf);
// We're done sending the message, set the radio back into recieve mode. // We're done sending the message, set the radio back into recieve mode.
Serial.println("sent");
radio.setModeReceive(); radio.setModeReceive();
radio.lookForTone(MORSE_FREQ); Serial.println("sent");
} else { } else {
// If we get here, the channel is busy. Let's also print out the RSSI. // If we get here, the channel is busy. Let's also print out the RSSI.
Serial.print("The channel was busy. RSSI: "); Serial.print("The channel was busy. RSSI: ");
@ -125,4 +171,33 @@ void loop() {
} }
} }
void handleTone(uint16_t tone_time) {
//Serial.println(tone_time);
if (tone_time > MIN_DOT_TIME && tone_time < MAX_DOT_TIME) {
// add a dot
//Serial.print(".");
//nothing to do for this bit position, since . = 0
} else if (tone_time > MIN_DASH_TIME && tone_time < MAX_DASH_TIME) {
// add a dash
//Serial.print("-");
rx_morse_char += rx_morse_bit;
}
// prep for the next bit
rx_morse_bit = rx_morse_bit << 1;
}
char parseMorse() {
// if morse_char is a valid morse character, return the character
// if morse_char is an invalid (incomplete) morse character, return 0
//if (rx_morse_bit != 1) Serial.println(rx_morse_char, BIN);
rx_morse_char += rx_morse_bit; // add the terminator bit
// if we got a char, then print it
char c = radio.morseReverseLookup(rx_morse_char);
rx_morse_char = 0;
rx_morse_bit = 1;
return c;
}

View File

@ -10,7 +10,7 @@
* 446MHz to receive the image output. * 446MHz to receive the image output.
*/ */
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -28,14 +28,13 @@ int16_t rssi;
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up

View File

@ -16,7 +16,7 @@
#include <HamShield.h> #include <HamShield.h>
#include <DDS.h> #include <DDS.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -32,14 +32,13 @@ ddsAccumulator_t freqTable[3];
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -55,7 +54,7 @@ void setup() {
// Tell the HamShield to start up // Tell the HamShield to start up
radio.initialize(); radio.initialize();
radio.setRfPower(0); radio.setRfPower(0);
radio.frequency(446000); radio.frequency(145500);
// put your setup code here, to run once: // put your setup code here, to run once:
//dds.setReferenceClock(34965/4); //dds.setReferenceClock(34965/4);
dds.start(); dds.start();

View File

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

View File

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

View File

@ -25,7 +25,7 @@ char CALLSIGN[] = "1ZZ9ZZ/B";
#include <HamShield.h> #include <HamShield.h>
#include <PCM.h> #include <PCM.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -90,14 +90,13 @@ const unsigned char dbm[] PROGMEM = {
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, LOW); digitalWrite(PWM_PIN, LOW);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -107,7 +106,7 @@ void setup() {
int result = radio.testConnection(); int result = radio.testConnection();
Serial.println(result); Serial.println(result);
radio.initialize(); radio.initialize();
radio.frequency(432400); radio.frequency(446000);
radio.setVolume1(0xF); radio.setVolume1(0xF);
radio.setVolume2(0xF); radio.setVolume2(0xF);
radio.setModeReceive(); radio.setModeReceive();

View File

@ -2,10 +2,6 @@
* Example: SpeechTX - This example used the basic JustTransmit example from the above site * Example: SpeechTX - This example used the basic JustTransmit example from the above site
* This example uses the Talkie Arduino speech library. It transmits pre-encoded speech over the air. * This example uses the Talkie Arduino speech library. It transmits pre-encoded speech over the air.
* More info at: https://github.com/going-digital/Talkie * More info at: https://github.com/going-digital/Talkie
*
* Make sure you're using an Arduino Uno or equivalent. The Talkie library doesn't work
* with hardware that doesn't use the ATMega328 or ATMega168.
*
* Connect the HamShield to your Arduino. Screw the antenna * Connect the HamShield to your Arduino. Screw the antenna
* into the HamShield RF jack. Connect the Arduino to * into the HamShield RF jack. Connect the Arduino to
* wall power and then to your computer via USB. After * wall power and then to your computer via USB. After
@ -16,7 +12,7 @@
#include <HamShield.h> #include <HamShield.h>
#define MIC_PIN 3 #define PWM_PIN 3
#define RESET_PIN A3 #define RESET_PIN A3
#define SWITCH_PIN 2 #define SWITCH_PIN 2
@ -234,14 +230,13 @@ const uint8_t spYELLOW[] PROGMEM = {0x69,0xBD,0x56,0x15,0xAC,0x67,0xE5,0x
void setup() { void setup() {
// NOTE: if not using PWM out, it should be held low to avoid tx noise // NOTE: if not using PWM out, it should be held low to avoid tx noise
pinMode(MIC_PIN, OUTPUT); pinMode(PWM_PIN, OUTPUT);
digitalWrite(MIC_PIN, HIGH); digitalWrite(PWM_PIN, HIGH);
// prep the switch // prep the switch
pinMode(SWITCH_PIN, INPUT_PULLUP); pinMode(SWITCH_PIN, INPUT_PULLUP);
// set up the reset control pin // set up the reset control pin
// NOTE: HamShieldMini doesn't have a reset pin, so this has no effect
pinMode(RESET_PIN, OUTPUT); pinMode(RESET_PIN, OUTPUT);
digitalWrite(RESET_PIN, HIGH); digitalWrite(RESET_PIN, HIGH);
delay(5); // wait for device to come up delay(5); // wait for device to come up
@ -254,16 +249,9 @@ void setup() {
Serial.println("Setting radio to its defaults.."); Serial.println("Setting radio to its defaults..");
radio.initialize(); radio.initialize();
radio.setRfPower(0); radio.setRfPower(0);
radio.frequency(145010); radio.frequency(144025);
}
void loop() {
radio.waitForChannel(); // wait for the channel to be empty
radio.setModeTransmit(); radio.setModeTransmit();
delay(100); // wait for PA to come up
voice.say(spKILO); // to change these to the words you would like to say, or a ham radio call sign - uncomment above encoded words voice.say(spKILO); // to change these to the words you would like to say, or a ham radio call sign - uncomment above encoded words
voice.say(spSIX); // more word choices can be found at the talkie github site voice.say(spSIX); // more word choices can be found at the talkie github site
voice.say(spALPHA); voice.say(spALPHA);
@ -279,6 +267,10 @@ void loop() {
voice.say(spON); voice.say(spON);
voice.say(spFIRE); voice.say(spFIRE);
radio.setModeReceive(); }
delay(10000);
void loop() {
radio.frequency(144025);
radio.setModeTransmit();
for(;;) { }
} }

View File

@ -1,5 +1,5 @@
name=HamShield name=HamShield
version=1.1.4 version=1.1.1
author=Morgan Redfield <morgan@enhancedradio.com>, Casey Halverson <casey@enhancedradio.com> author=Morgan Redfield <morgan@enhancedradio.com>, Casey Halverson <casey@enhancedradio.com>
maintainer=Morgan Redfield <morgan@enhancedradio.com> maintainer=Morgan Redfield <morgan@enhancedradio.com>
sentence=A library for use with HamShield by Enhanced Radio Devices. sentence=A library for use with HamShield by Enhanced Radio Devices.

File diff suppressed because it is too large Load Diff

View File

@ -9,12 +9,22 @@
#define _HAMSHIELD_H_ #define _HAMSHIELD_H_
#include "HamShield_comms.h" #include "HamShield_comms.h"
//#include "SimpleFIFO.h"
//#include "AFSK.h"
//#include "DDS.h"
#include <avr/pgmspace.h>
// HamShield constants // HamShield constants
#define HAMSHIELD_MORSE_BUFFER_SIZE 80 // Char buffer size for morse code text #define HAMSHIELD_MORSE_BUFFER_SIZE 80 // Char buffer size for morse code text
#define HAMSHIELD_AUX_BUTTON 2 // Pin assignment for AUX button
#define HAMSHIELD_PWM_PIN 3 // Pin assignment for PWM output
#define HAMSHIELD_EMPTY_CHANNEL_RSSI -110 // Default threshold where channel is considered "clear" #define HAMSHIELD_EMPTY_CHANNEL_RSSI -110 // Default threshold where channel is considered "clear"
// button modes
#define PTT_MODE 1
#define RESET_MODE 2
// Device Registers // Device Registers
#define A1846S_CTL_REG 0x30 // control register #define A1846S_CTL_REG 0x30 // control register
#define A1846S_CLK_MODE_REG 0x04 // clk_mode #define A1846S_CLK_MODE_REG 0x04 // clk_mode
@ -28,11 +38,11 @@
//#define A1846S_ADCLK_FREQ_REG 0x2C // adclk_freq<15:0> //#define A1846S_ADCLK_FREQ_REG 0x2C // adclk_freq<15:0>
#define A1846S_INT_MODE_REG 0x2D // interrupt enables #define A1846S_INT_MODE_REG 0x2D // interrupt enables
#define A1846S_TX_VOICE_REG 0x3A // tx voice control reg #define A1846S_TX_VOICE_REG 0x3A // tx voice control reg
#define A1846S_TH_H_VOX_REG 0x64 // register holds vox high (open) threshold bits #define A1846S_TH_H_VOX_REG 0x41 // register holds vox high (open) threshold bits
#define A1846S_TH_L_VOX_REG 0x64 // register holds vox low (shut) threshold bits #define A1846S_TH_L_VOX_REG 0x42 // register holds vox low (shut) threshold bits
#define A1846S_FM_DEV_REG 0x43 // register holds fm deviation settings #define A1846S_FM_DEV_REG 0x43 // register holds fm deviation settings
#define A1846S_RX_VOLUME_REG 0x44 // register holds RX volume settings #define A1846S_RX_VOLUME_REG 0x44 // register holds RX volume settings
#define A1846S_SQ_OPEN_THRESH_REG 0x49 // see sq #define A1846S_SQ_OPEN_THRESH_REG 0x48 // see sq
#define A1846S_SQ_SHUT_THRESH_REG 0x49 // see sq #define A1846S_SQ_SHUT_THRESH_REG 0x49 // see sq
#define A1846S_CTCSS_FREQ_REG 0x4A // ctcss_freq<15:0> #define A1846S_CTCSS_FREQ_REG 0x4A // ctcss_freq<15:0>
#define A1846S_CDCSS_CODE_HI_REG 0x4B // cdcss_code<23:16> #define A1846S_CDCSS_CODE_HI_REG 0x4B // cdcss_code<23:16>
@ -105,7 +115,7 @@
#define A1846S_TXON_RF_INT_BIT 7 // txon_rf_uint16_t enable #define A1846S_TXON_RF_INT_BIT 7 // txon_rf_uint16_t enable
#define A1846S_CTCSS_PHASE_INT_BIT 5 // ctcss phase shift detect uint16_t enable #define A1846S_CTCSS_PHASE_INT_BIT 5 // ctcss phase shift detect uint16_t enable
#define A1846S_IDLE_TIMEOUT_INT_BIT 4 // idle state time out uint16_t enable #define A1846S_IDLE_TIMEOUT_INT_BIT 4 // idle state time out uint16_t enable
#define A1846S_RXON_RF_TIMEOUT_INT_BIT 3 // rxon_rf timerout uint16_t enable #define A1846S_RXON_RF_TIMeOUT_INT_BIT 3 // rxon_rf timerout uint16_t enable
#define A1846S_SQ_INT_BIT 2 // sq uint16_t enable #define A1846S_SQ_INT_BIT 2 // sq uint16_t enable
#define A1846S_TXON_RF_TIMEOUT_INT_BIT 1 // txon_rf time out uint16_t enable #define A1846S_TXON_RF_TIMEOUT_INT_BIT 1 // txon_rf time out uint16_t enable
#define A1846S_VOX_INT_BIT 0 // vox uint16_t enable #define A1846S_VOX_INT_BIT 0 // vox uint16_t enable
@ -116,12 +126,8 @@
#define A1846S_CTCSS_DET_BIT 5 #define A1846S_CTCSS_DET_BIT 5
// Bitfields for A1846S_TH_H_VOX_REG // Bitfields for A1846S_TH_H_VOX_REG
#define A1846S_TH_H_VOX_BIT 13 // th_h_vox<13:7> #define A1846S_TH_H_VOX_BIT 14 // th_h_vox<14:0>
#define A1846S_TH_H_VOX_LEN 7 #define A1846S_TH_H_VOX_LENGTH 15
// Bitfields for A1846S_TH_L_VOX_REG
#define A1846S_TH_L_VOX_BIT 6 // th_l_vox<6:0>
#define A1846S_TH_L_VOX_LEN 7
// Bitfields for A1846S_FM_DEV_REG // Bitfields for A1846S_FM_DEV_REG
#define A1846S_FM_DEV_VOICE_BIT 12 // CTCSS/CDCSS and voice deviation <6:0> #define A1846S_FM_DEV_VOICE_BIT 12 // CTCSS/CDCSS and voice deviation <6:0>
@ -145,12 +151,12 @@
#define A1846S_SHIFT_SEL_LEN 2 #define A1846S_SHIFT_SEL_LEN 2
// Bitfields for A1846S_SQ_THRESH_REG // Bitfields for A1846S_SQ_THRESH_REG
#define A1846S_SQ_OPEN_THRESH_BIT 13 // sq open threshold <6:0> #define A1846S_SQ_OPEN_THRESH_BIT 9 // sq open threshold <9:0>
#define A1846S_SQ_OPEN_THRESH_LENGTH 7 #define A1846S_SQ_OPEN_THRESH_LENGTH 10
// Bitfields for A1846S_SQ_SHUT_THRESH_REG // Bitfields for A1846S_SQ_SHUT_THRESH_REG
#define A1846S_SQ_SHUT_THRESH_BIT 6 // sq shut threshold <6:0> #define A1846S_SQ_SHUT_THRESH_BIT 9 // sq shut threshold <9:0>
#define A1846S_SQ_SHUT_THRESH_LENGTH 7 #define A1846S_SQ_SHUT_THRESH_LENGTH 10
// Bitfields for A1846S_SQ_OUT_SEL_REG // Bitfields for A1846S_SQ_OUT_SEL_REG
#define A1846S_SQ_OUT_SEL_BIT 7 // sq_out_sel #define A1846S_SQ_OUT_SEL_BIT 7 // sq_out_sel
@ -168,18 +174,16 @@
#define A1846S_CTCSS2_FLAG_BIT 8 // 1 when txon is enabled #define A1846S_CTCSS2_FLAG_BIT 8 // 1 when txon is enabled
#define A1846S_INVERT_DET_FLAG_BIT 7 // ctcss phase shift detect #define A1846S_INVERT_DET_FLAG_BIT 7 // ctcss phase shift detect
#define A1846S_CSS_CMP_FLAG_BIT 2 // ctcss/cdcss compared #define A1846S_CSS_CMP_FLAG_BIT 2 // ctcss/cdcss compared
#define A1846S_SQ_FLAG_BIT 0 // sq final signal out from dsp #define A1846S_SQ_FLAG_BIT 1 // sq final signal out from dsp
#define A1846S_VOX_FLAG_BIT 1 // vox out from dsp #define A1846S_VOX_FLAG_BIT 0 // vox out from dsp
// Bitfields for A1846S_RSSI_REG // Bitfields for A1846S_RSSI_REG
#define A1846S_RSSI_BIT 15 // RSSI readings <7:0> #define A1846S_RSSI_BIT 15 // RSSI readings <7:0>
#define A1846S_RSSI_LENGTH 8 #define A1846S_RSSI_LENGTH 8
// Bitfields for A1846S_VSSI_REG // Bitfields for A1846S_VSSI_REG
#define A1846S_VSSI_BIT 15 // voice signal strength indicator <7:0> (unit 0.5dB) #define A1846S_VSSI_BIT 14 // voice signal strength indicator <14:0> (unit mV)
#define A1846S_VSSI_LENGTH 8 #define A1846S_VSSI_LENGTH 15
#define A1846S_MSSI_BIT 7 // mic signal strength <7:0> (unit 0.5 dB)
#define A1846S_MSSI_LENGTH 8
// Bitfields for A1846S_DTMF_ENABLE_REG // Bitfields for A1846S_DTMF_ENABLE_REG
#define A1846S_DTMF_ENABLE_BIT 15 #define A1846S_DTMF_ENABLE_BIT 15
@ -217,24 +221,14 @@
#define HAMSHIELD_PSK31_FREQ 1000 #define HAMSHIELD_PSK31_FREQ 1000
// Morse Configuration
#define MORSE_FREQ 600
#define MORSE_DOT 150 // ms
#define SYMBOL_END_TIME 5 //millis
#define CHAR_END_TIME (MORSE_DOT*2.7)
#define MESSAGE_END_TIME (MORSE_DOT*8)
#define MIN_DOT_TIME (MORSE_DOT-30)
#define MAX_DOT_TIME (MORSE_DOT+55)
#define MIN_DASH_TIME (MORSE_DOT*3-30)
#define MAX_DASH_TIME (MORSE_DOT*3+55)
class HamShield { class HamShield {
public: public:
HamShield(uint8_t ncs_pin = nCS, uint8_t clk_pin = CLK, uint8_t dat_pin = DAT, uint8_t mic_pin = MIC); // public singleton for ISRs to reference
static HamShield *sHamShield; // HamShield singleton, used for ISRs mostly
HamShield();
HamShield(uint8_t cs_pin);
void initialize(); // defaults to 12.5kHz void initialize(); // defaults to 12.5kHz
void initialize(bool narrowBand); // select 12.5kHz if true or 25kHz if false void initialize(bool narrowBand); // select 12.5kHz if true or 25kHz if false
@ -255,14 +249,12 @@ class HamShield {
uint32_t getFrequency(); uint32_t getFrequency();
float getFrequency_float(); float getFrequency_float();
/* ToDo
// channel mode // channel mode
// 11 - 25kHz channel // 11 - 25kHz channel
// 00 - 12.5kHz channel // 00 - 12.5kHz channel
// 10,01 - reserved // 10,01 - reserved
void setChanMode(uint16_t mode); void setChanMode(uint16_t mode);
uint16_t getChanMode(); uint16_t getChanMode();
*/
void setModeTransmit(); // turn off rx, turn on tx void setModeTransmit(); // turn off rx, turn on tx
void setModeReceive(); // turn on rx, turn off tx void setModeReceive(); // turn on rx, turn off tx
@ -281,7 +273,6 @@ class HamShield {
void setTxSourceNone(); void setTxSourceNone();
uint16_t getTxSource(); uint16_t getTxSource();
/*
// PA bias voltage is unused (maybe remove this) // PA bias voltage is unused (maybe remove this)
// set PA_bias voltage // set PA_bias voltage
// 000000: 1.01V // 000000: 1.01V
@ -294,7 +285,6 @@ class HamShield {
// 1111111:3.13V // 1111111:3.13V
void setPABiasVoltage(uint16_t voltage); void setPABiasVoltage(uint16_t voltage);
uint16_t getPABiasVoltage(); uint16_t getPABiasVoltage();
*/
// Subaudio settings // Subaudio settings
@ -313,11 +303,7 @@ class HamShield {
uint16_t getCtcssFreqMilliHz(); uint16_t getCtcssFreqMilliHz();
float getCtcssFreqHz(); float getCtcssFreqHz();
void setCtcssFreqToStandard(); // freq must be 134.4Hz for standard cdcss mode void setCtcssFreqToStandard(); // freq must be 134.4Hz for standard cdcss mode
void enableCtcssTx();
void enableCtcssRx();
void enableCtcss(); void enableCtcss();
void disableCtcssTx();
void disableCtcssRx();
void disableCtcss(); void disableCtcss();
void setCtcssDetThreshIn(uint8_t thresh); void setCtcssDetThreshIn(uint8_t thresh);
uint8_t getCtcssDetThreshIn(); uint8_t getCtcssDetThreshIn();
@ -362,7 +348,6 @@ class HamShield {
int16_t getSQHiThresh(); 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 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(); int16_t getSQLoThresh();
bool getSquelching();
// SQ out select // SQ out select
void setSQOutSel(); void setSQOutSel();
@ -408,9 +393,6 @@ class HamShield {
uint16_t getDTMFDetectTime(); uint16_t getDTMFDetectTime();
void setDTMFIdleTime(uint16_t idle_time); // idle time is time between DTMF Tone void setDTMFIdleTime(uint16_t idle_time); // idle time is time between DTMF Tone
uint16_t getDTMFIdleTime(); uint16_t getDTMFIdleTime();
char DTMFRxLoop();
char DTMFcode2char(uint16_t code);
uint8_t DTMFchar2code(char c);
void setDTMFTxTime(uint16_t tx_time); // tx time is duration of DTMF Tone void setDTMFTxTime(uint16_t tx_time); // tx time is duration of DTMF Tone
uint16_t getDTMFTxTime(); uint16_t getDTMFTxTime();
uint16_t disableDTMF(); uint16_t disableDTMF();
@ -420,8 +402,6 @@ class HamShield {
void setDTMFCode(uint16_t code); void setDTMFCode(uint16_t code);
// Tone // Tone
void HStone(uint8_t pin, unsigned int frequency);
void HSnoTone(uint8_t pin);
void lookForTone(uint16_t tone_hz); void lookForTone(uint16_t tone_hz);
uint8_t toneDetected(); uint8_t toneDetected();
@ -486,7 +466,6 @@ class HamShield {
// Read Only Status Registers // Read Only Status Registers
int16_t readRSSI(); int16_t readRSSI();
uint16_t readVSSI(); uint16_t readVSSI();
uint16_t readMSSI();
// set output power of radio // set output power of radio
void setRfPower(uint8_t pwr); void setRfPower(uint8_t pwr);
@ -503,19 +482,17 @@ class HamShield {
uint32_t findWhitespace(uint32_t start,uint32_t stop, uint8_t dwell, uint16_t step, uint16_t threshold); uint32_t findWhitespace(uint32_t start,uint32_t stop, uint8_t dwell, uint16_t step, uint16_t threshold);
uint32_t scanChannels(uint32_t buffer[],uint8_t buffsize, uint8_t speed, uint16_t threshold); uint32_t scanChannels(uint32_t buffer[],uint8_t buffsize, uint8_t speed, uint16_t threshold);
uint32_t findWhitespaceChannels(uint32_t buffer[],uint8_t buffsize, uint8_t dwell, uint16_t threshold); uint32_t findWhitespaceChannels(uint32_t buffer[],uint8_t buffsize, uint8_t dwell, uint16_t threshold);
void buttonMode(uint8_t mode);
void setupMorseRx(); static void isr_ptt();
static void isr_reset();
unsigned int getMorseFreq(); unsigned int getMorseFreq();
void setMorseFreq(unsigned int morse_freq_hz); void setMorseFreq(unsigned int morse_freq_hz);
unsigned int getMorseDotMillis(); unsigned int getMorseDotMillis();
void setMorseDotMillis(unsigned int morse_dot_dur_millis); void setMorseDotMillis(unsigned int morse_dot_dur_millis);
void morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]); void morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]);
char morseRxLoop();
bool handleMorseTone(uint16_t tone_time, bool bits_to_process, uint8_t * rx_morse_char, uint8_t * rx_morse_bit);
char parseMorse(uint8_t rx_morse_char, uint8_t rx_morse_bit);
uint8_t morseLookup(char letter); uint8_t morseLookup(char letter);
uint8_t morseReverseLookup(uint8_t itu); uint8_t morseReverseLookup(uint8_t itu);
bool waitForChannel(long timeout = 0, long breakwindow = 0, int setRSSI = HAMSHIELD_EMPTY_CHANNEL_RSSI); bool waitForChannel(long timeout, long breakwindow, int setRSSI);
void SSTVVISCode(int code); void SSTVVISCode(int code);
void SSTVTestPattern(int code); void SSTVTestPattern(int code);
void toneWait(uint16_t freq, long timer); void toneWait(uint16_t freq, long timer);
@ -526,8 +503,7 @@ class HamShield {
private: private:
uint8_t devAddr; uint8_t devAddr;
uint8_t hs_mic_pin; uint16_t radio_i2c_buf[4];
uint16_t radio_dat_buf[4];
bool tx_active; bool tx_active;
bool rx_active; bool rx_active;
float radio_frequency; float radio_frequency;

View File

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

View File

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