Initial commit of HamShield library and example sketches. Probably not fully functional.
This commit is contained in:
parent
c551fd9508
commit
23ba8f6e7c
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,8 @@
|
||||||
|
chrome.app.runtime.onLaunched.addListener(function() {
|
||||||
|
chrome.app.window.create("window.html", {
|
||||||
|
"bounds": {
|
||||||
|
"width": 400,
|
||||||
|
"height": 500
|
||||||
|
}
|
||||||
|
});
|
||||||
|
});
|
|
@ -0,0 +1,10 @@
|
||||||
|
{
|
||||||
|
"name": "",
|
||||||
|
"description": "HAMShield",
|
||||||
|
"version": "1.0.0",
|
||||||
|
"app": {
|
||||||
|
"background": {
|
||||||
|
"scripts": ["background.js"]
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1 @@
|
||||||
|
chromeApp
|
|
@ -0,0 +1 @@
|
||||||
|
body{}
|
|
@ -0,0 +1,13 @@
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div>
|
||||||
|
Power
|
||||||
|
</div>
|
||||||
|
<div>
|
||||||
|
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
|
@ -0,0 +1,53 @@
|
||||||
|
/*
|
||||||
|
|
||||||
|
Morse Code Beacon
|
||||||
|
|
||||||
|
Test beacon will transmit and wait 30 seconds.
|
||||||
|
Beacon will check to see if the channel is clear before it will transmit.
|
||||||
|
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(9600);
|
||||||
|
Serial.println("starting up..");
|
||||||
|
Wire.begin();
|
||||||
|
|
||||||
|
pinMode(11, OUTPUT);
|
||||||
|
|
||||||
|
//testing
|
||||||
|
//Wire.beginTransmission(42);
|
||||||
|
//Wire.write('T');
|
||||||
|
//Wire.write('e');
|
||||||
|
//Wire.write('s');
|
||||||
|
//Wire.write('t');
|
||||||
|
//Wire.endTransmission();
|
||||||
|
|
||||||
|
|
||||||
|
Serial.print("Radio status: ");
|
||||||
|
int result = radio.testConnection();
|
||||||
|
Serial.println(result,DEC);
|
||||||
|
radio.initialize(); // setup radio
|
||||||
|
radio.setFrequency(446000); // set to 70 cm call frequency
|
||||||
|
Serial.println("Done with radio beacon setup.");
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
//while(1){}
|
||||||
|
//if(radio.waitForChannel(30000,2000)) { // wait up to 30 seconds for a clear channel, and then 2 seconds of empty channel
|
||||||
|
Serial.println("Signal is clear -- Transmitting");
|
||||||
|
radio.setModeTransmit(); // turn on the transmitter
|
||||||
|
radio.morseOut("1ZZ9ZZ/B CN87 ARDUINO HAMSHIELD");
|
||||||
|
radio.setModeReceive(); // turn off the transmitter (receive mode)
|
||||||
|
Serial.print("TX Off");
|
||||||
|
//delay(30000);
|
||||||
|
//} else { Serial.println("The channel was busy. Waiting 10 seconds."); delay(10000); }
|
||||||
|
delay(10000);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,283 @@
|
||||||
|
|
||||||
|
// BlueHAM Proto01 Connection Guide
|
||||||
|
/**********************
|
||||||
|
**
|
||||||
|
** BlueHAM Proto01 <--> Arduino
|
||||||
|
** ADC_SCL A5
|
||||||
|
** ADC_DIO A4
|
||||||
|
** GND GND
|
||||||
|
** PWM_RF_CTL D9
|
||||||
|
**
|
||||||
|
** Setting Connections
|
||||||
|
** MODE -> GND
|
||||||
|
** SENB -> GND
|
||||||
|
** PDN -> 3.3V
|
||||||
|
** AVDD -> 5V (note this should be a beefy supply, could draw up to 4As)
|
||||||
|
**
|
||||||
|
**
|
||||||
|
**
|
||||||
|
** Pinout information for RadioPeripheral01 Prototype board
|
||||||
|
** GPIO0 -
|
||||||
|
** GPIO1 -
|
||||||
|
** GPIO2 - VHF_SEL
|
||||||
|
** GPIO3 - UHF_SEL
|
||||||
|
** GPIO4 - RX_EN
|
||||||
|
** GPIO5 - TX_EN
|
||||||
|
** GPIO6 -
|
||||||
|
** GPIO7 -
|
||||||
|
**************************/
|
||||||
|
|
||||||
|
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
|
||||||
|
// is used in I2Cdev.h
|
||||||
|
#include "Wire.h"
|
||||||
|
#include "HAMShield.h"
|
||||||
|
|
||||||
|
#include <Goertzel.h>
|
||||||
|
|
||||||
|
//typedef enum {
|
||||||
|
#define MAIN_S 0
|
||||||
|
#define RX_S 1
|
||||||
|
#define TX_S 2
|
||||||
|
#define FREQ_S 3
|
||||||
|
#define UHF_S 4
|
||||||
|
#define VHF_S 5
|
||||||
|
#define PWR_S 6
|
||||||
|
#define GPIO_S 7
|
||||||
|
//} menu_view;
|
||||||
|
|
||||||
|
int state;
|
||||||
|
|
||||||
|
/* goertzel routines */
|
||||||
|
|
||||||
|
int sensorPin = A0;
|
||||||
|
int led = 13;
|
||||||
|
const float TARGET_FREQUENCY = 2200;
|
||||||
|
const int N = 100;
|
||||||
|
const float THRESHOLD = 4000;
|
||||||
|
const float SAMPLING_FREQUENCY = 8900;
|
||||||
|
Goertzel goertzel = Goertzel(TARGET_FREQUENCY, N, SAMPLING_FREQUENCY);
|
||||||
|
|
||||||
|
// create object for RDA
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
|
||||||
|
#define LED_PIN 13
|
||||||
|
bool blinkState = false;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
// initialize serial communication
|
||||||
|
Serial.begin(115200);
|
||||||
|
Serial.println("beginning radio setup");
|
||||||
|
|
||||||
|
// join I2C bus (I2Cdev library doesn't do this automatically)
|
||||||
|
Wire.begin();
|
||||||
|
|
||||||
|
// verify connection
|
||||||
|
Serial.println("Testing device connections...");
|
||||||
|
Serial.println(radio.testConnection() ? "RDA radio connection successful" : "RDA radio connection failed");
|
||||||
|
|
||||||
|
// initialize device
|
||||||
|
Serial.println("Initializing I2C devices...");
|
||||||
|
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
|
||||||
|
|
||||||
|
Serial.println("setting default Radio configuration");
|
||||||
|
|
||||||
|
|
||||||
|
// set frequency
|
||||||
|
Serial.println("changing frequency");
|
||||||
|
|
||||||
|
|
||||||
|
radio.setFrequency(446000); // in kHz
|
||||||
|
radio.setModeReceive();
|
||||||
|
|
||||||
|
// configure Arduino LED for
|
||||||
|
pinMode(LED_PIN, OUTPUT);
|
||||||
|
|
||||||
|
state = MAIN_S;
|
||||||
|
print_menu();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
goertzel.sample(sensorPin);
|
||||||
|
float magnitude = goertzel.detect();
|
||||||
|
if(magnitude>THRESHOLD) digitalWrite(led, HIGH); //if found, enable led
|
||||||
|
else digitalWrite(led, LOW);
|
||||||
|
while (Serial.available()) {
|
||||||
|
if (state == FREQ_S) {
|
||||||
|
char freq_khz[6];
|
||||||
|
int i = 0;
|
||||||
|
while(i < 6) {
|
||||||
|
if (Serial.available()) {
|
||||||
|
freq_khz[i] = Serial.read();
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// interpret frequency
|
||||||
|
uint32_t freq = 0;
|
||||||
|
i = 0;
|
||||||
|
while (i < 6) {
|
||||||
|
uint32_t temp = freq_khz[i] - '0';
|
||||||
|
for (int k = 5-i; k > 0; k--) {
|
||||||
|
temp = temp * 10;
|
||||||
|
}
|
||||||
|
freq += temp;
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
Serial.print("setting frequency to: ");
|
||||||
|
Serial.println(freq);
|
||||||
|
radio.setFrequency(freq);
|
||||||
|
state = MAIN_S;
|
||||||
|
|
||||||
|
} else if (state == PWR_S) {
|
||||||
|
uint8_t pwr_raw[3];
|
||||||
|
int i = 0;
|
||||||
|
while(i < 3) {
|
||||||
|
if (Serial.available()) {
|
||||||
|
pwr_raw[i] = Serial.read();
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// interpret power
|
||||||
|
uint8_t pwr = 0;
|
||||||
|
i = 0;
|
||||||
|
while (i < 3) {
|
||||||
|
uint8_t temp = pwr_raw[i] - '0';
|
||||||
|
for (int k = 2-i; k > 0; k--) {
|
||||||
|
temp = temp * 10;
|
||||||
|
}
|
||||||
|
pwr += temp;
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.print("Setting power to: ");
|
||||||
|
Serial.println(pwr);
|
||||||
|
radio.setRfPower(pwr);
|
||||||
|
state = MAIN_S;
|
||||||
|
|
||||||
|
} else if (state == GPIO_S) {
|
||||||
|
uint8_t gpio_raw[2];
|
||||||
|
int i = 0;
|
||||||
|
while(i < 2) {
|
||||||
|
if (Serial.available()) {
|
||||||
|
gpio_raw[i] = Serial.read();
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
uint16_t gpio_pin = gpio_raw[0] - 48; // '0';
|
||||||
|
uint16_t gpio_mode = gpio_raw[1] - 48;
|
||||||
|
|
||||||
|
radio.setGpioMode(gpio_pin, gpio_mode);
|
||||||
|
state = MAIN_S;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
char action = Serial.read();
|
||||||
|
if (action == 'r') { // get current state
|
||||||
|
state = RX_S;
|
||||||
|
} else if (action == 't') {
|
||||||
|
state = TX_S;
|
||||||
|
} else if (action == 'f') {
|
||||||
|
state = FREQ_S;
|
||||||
|
} else if (action == 'u') {
|
||||||
|
state = UHF_S;
|
||||||
|
} else if (action == 'v') {
|
||||||
|
state = VHF_S;
|
||||||
|
} else if (action == '1') {
|
||||||
|
turn_on(state);
|
||||||
|
state = MAIN_S;
|
||||||
|
} else if (action == '0') {
|
||||||
|
turn_off(state);
|
||||||
|
state = MAIN_S;
|
||||||
|
} else if (action == 'p') {
|
||||||
|
state = PWR_S;
|
||||||
|
} else if (action == 'g') {
|
||||||
|
state = GPIO_S;
|
||||||
|
} else if (action == 's') {
|
||||||
|
int16_t rssi = radio.readRSSI();
|
||||||
|
Serial.print("rssi: ");
|
||||||
|
Serial.println(rssi);
|
||||||
|
} else if (action == 'i') {
|
||||||
|
int16_t vssi = radio.readVSSI();
|
||||||
|
Serial.print("vssi: ");
|
||||||
|
Serial.println(vssi);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println(action);
|
||||||
|
}
|
||||||
|
Serial.flush();
|
||||||
|
print_menu();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void turn_off(int dev) {
|
||||||
|
switch (dev) {
|
||||||
|
case RX_S:
|
||||||
|
radio.setRX(0);
|
||||||
|
break;
|
||||||
|
case TX_S:
|
||||||
|
radio.setTX(0);
|
||||||
|
break;
|
||||||
|
case UHF_S:
|
||||||
|
radio.setGpioMode(3, 3); // set GPIO3 high (uhf is active low)
|
||||||
|
break;
|
||||||
|
case VHF_S:
|
||||||
|
radio.setGpioMode(2, 3); // set GPIO2 high (vhf is active low)
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void turn_on(int dev) {
|
||||||
|
switch (dev) {
|
||||||
|
case RX_S:
|
||||||
|
radio.setRX(1);
|
||||||
|
break;
|
||||||
|
case TX_S:
|
||||||
|
radio.setTX(1);
|
||||||
|
break;
|
||||||
|
case UHF_S:
|
||||||
|
radio.setGpioMode(3, 2); // set GPIO3 low (uhf is active low)
|
||||||
|
break;
|
||||||
|
case VHF_S:
|
||||||
|
radio.setGpioMode(2, 2); // set GPIO2 low (uhf is active low)
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_menu() {
|
||||||
|
Serial.println("MENU");
|
||||||
|
switch (state) {
|
||||||
|
case MAIN_S:
|
||||||
|
Serial.println("select step: [r]x, [t]x, [f]req, [u]hf, [v]hf, [p]wr, [g]pio control, r[s]si, vss[i] ...");
|
||||||
|
break;
|
||||||
|
case RX_S:
|
||||||
|
Serial.println("enter 1 to turn on rx, 0 to turn off rx");
|
||||||
|
break;
|
||||||
|
case TX_S:
|
||||||
|
Serial.println("enter 1 to turn on tx, 0 to turn off tx");
|
||||||
|
break;
|
||||||
|
case FREQ_S:
|
||||||
|
Serial.println("enter frequency in kHz (ffffff)");
|
||||||
|
break;
|
||||||
|
case UHF_S:
|
||||||
|
Serial.println("enter 1 to turn on uhf, 0 to turn off uhf");
|
||||||
|
break;
|
||||||
|
case VHF_S:
|
||||||
|
Serial.println("enter 1 to turn on vhf, 0 to turn off vhf");
|
||||||
|
break;
|
||||||
|
case PWR_S:
|
||||||
|
Serial.println("enter power (raw) (ppp)");
|
||||||
|
break;
|
||||||
|
case GPIO_S:
|
||||||
|
Serial.println("enter GPIO pin and control (no spaces, eg pin 1 mode 3 is 13");
|
||||||
|
Serial.println("modes 0 - HiZ, 1 - FCN, 2 - Low, 3 - Hi");
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
state = MAIN_S;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,37 @@
|
||||||
|
/* Fox Hunt */
|
||||||
|
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
// transmit for 1 minute, every 10 minutes
|
||||||
|
|
||||||
|
#define TRANSMITLENGTH 1
|
||||||
|
#define INTERVAL 10
|
||||||
|
#define RANDOMCHANCE 3
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Wire.begin();
|
||||||
|
radio.initialize();
|
||||||
|
radio.setFrequency(145510);
|
||||||
|
radio.setModeReceive();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
waitMinute(INTERVAL + random(0,RANDOMCHANCE)); // wait before transmitting, randomly up to 3 minutes later
|
||||||
|
if(radio.waitForChannel(30000,2000)) { // wait for a clear channel, abort after 30 seconds, wait 2 seconds of dead air for breakers
|
||||||
|
radio.setModeTransmit(); // turn on transmit mode
|
||||||
|
tone(1000,11,TRANSMITLENGTH * 60 * 1000); // play a long solid tone
|
||||||
|
radio.morseOut("1ZZ9ZZ/B FOXHUNT"); // identify the fox hunt transmitter
|
||||||
|
radio.setModeReceive(); // turn off the transmit mode
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// a function so we can wait by minutes
|
||||||
|
|
||||||
|
void waitMinute(int period) {
|
||||||
|
delay(period * 60 * 1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,99 @@
|
||||||
|
/*
|
||||||
|
|
||||||
|
Gauges
|
||||||
|
|
||||||
|
Simple gauges for the radio receiver.
|
||||||
|
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
void clr() {
|
||||||
|
/* Serial.write(27);
|
||||||
|
Serial.print("[2J"); // cursor to home command */
|
||||||
|
Serial.write(27);
|
||||||
|
Serial.print("[H"); // cursor to home command
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
analogReference(DEFAULT);
|
||||||
|
Serial.begin(115200);
|
||||||
|
Wire.begin();
|
||||||
|
Serial.print("Radio status: ");
|
||||||
|
int result = radio.testConnection();
|
||||||
|
Serial.println(result,DEC);
|
||||||
|
radio.initialize();
|
||||||
|
radio.setFrequency(446000);
|
||||||
|
Serial.println("Entering gauges...");
|
||||||
|
tone(9,1000);
|
||||||
|
delay(2000);
|
||||||
|
}
|
||||||
|
|
||||||
|
int gauge;
|
||||||
|
int x = 0;
|
||||||
|
int y = 0;
|
||||||
|
int peak = 0;
|
||||||
|
int a = 0;
|
||||||
|
int mini = 0;
|
||||||
|
int vpeak = 0;
|
||||||
|
int txc = 0;
|
||||||
|
int mode = 0;
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
clr();
|
||||||
|
int16_t rssi = radio.readRSSI();
|
||||||
|
gauge = map(rssi,-123,-50,0,8);
|
||||||
|
Serial.print("[");
|
||||||
|
for(x = 0; x < gauge; x++) {
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
Serial.print("|");
|
||||||
|
for(y = x; y < 8; y++) {
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
Serial.print("] ");
|
||||||
|
Serial.print(rssi);
|
||||||
|
Serial.println(" ");
|
||||||
|
Serial.println("Signal \n");
|
||||||
|
|
||||||
|
// radio.setModeTransmit();
|
||||||
|
int16_t vssi = radio.readVSSI();
|
||||||
|
// radio.setModeReceive();
|
||||||
|
if(vssi > vpeak) { vpeak = vssi; }
|
||||||
|
gauge = map(vssi,-50,-150,0,8);
|
||||||
|
Serial.print("[");
|
||||||
|
for(x = 0; x < gauge; x++) {
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
Serial.print("|");
|
||||||
|
for(y = x; y < 8; y++) {
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
Serial.print("] ");
|
||||||
|
Serial.print(vpeak);
|
||||||
|
Serial.println(" ");
|
||||||
|
Serial.println("Audio In\n");
|
||||||
|
|
||||||
|
a = analogRead(0);
|
||||||
|
if(a > peak) { peak = a; }
|
||||||
|
if(a < mini) { mini = a; }
|
||||||
|
gauge = map(a,400,1023,0,8);
|
||||||
|
Serial.print("[");
|
||||||
|
for(x = 0; x < gauge; x++) {
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
Serial.print("|");
|
||||||
|
for(y = x; y < 8; y++) {
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
Serial.print("] ");
|
||||||
|
Serial.print(a,DEC);
|
||||||
|
Serial.print(" ("); Serial.print(peak,DEC); Serial.println(") ");
|
||||||
|
Serial.println("Audio RX ADC Peak\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,32 @@
|
||||||
|
/* Simple DTMF controlled HAM Radio Robot */
|
||||||
|
|
||||||
|
#include <ArduinoRobot.h> // include the robot library
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Robot.begin();
|
||||||
|
Wire.begin();
|
||||||
|
radio.initialize();
|
||||||
|
radio.setFrequency(145510);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
if(radio.waitForDTMF()) { // wait for a received DTMF tone
|
||||||
|
uint8_t command = radio.getLastDTMFDigit(); // get the last DTMF tone sent
|
||||||
|
if(command == '4') { Robot.turn(-90); } // turn robot left
|
||||||
|
if(command == '6') { Robot.turn(90); } // turn robot right
|
||||||
|
if(command == '2') { Robot.motorsWrite(-255,-255); delay(500); Robot.motorsWrite(255, 255); } // move robot forward
|
||||||
|
if(command == '5') { // tell robot to send morse code identity
|
||||||
|
if(radio.waitForChannel()) { // wait for the user to release the transmit button
|
||||||
|
radio.setModeTransmit(); // turn on transmit mode
|
||||||
|
radio.morseOut("1ZZ9ZZ I AM HAMRADIO ROBOT"); // send morse code
|
||||||
|
radio.setModeReceive(); // go back to receive mode on radio
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -0,0 +1,80 @@
|
||||||
|
/*
|
||||||
|
|
||||||
|
Indentifier
|
||||||
|
|
||||||
|
Arduino audio overlay example
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
#define DOT 100
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
const char *bascii = "ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789.,?'!/()&:;=+-_\"$@",
|
||||||
|
*bitu[] = { ".-","-...","-.-.","-..",".","..-.","--.","....","..",".---","-.-",".-..","--","-.","---",".--.","--.-",".-.","...","-","..-","...-",".--","-..-","-.--","--..","-----",".----","..---","...--","....-",".....","-....","--...","---..","----.",".-.-.-","--..--","..--..",".----.","-.-.--","-..-.","-.--.","-.--.-",".-...","---...","-.-.-.","-...-",".-.-.","-....-","..--.-",".-..-.","...-..-",".--.-."
|
||||||
|
};
|
||||||
|
|
||||||
|
const char *callsign = {"1ZZ9ZZ/B"} ;
|
||||||
|
|
||||||
|
char morsebuffer[8];
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(9600);
|
||||||
|
Serial.println("starting up..");
|
||||||
|
Wire.begin();
|
||||||
|
Serial.print("Radio status: ");
|
||||||
|
int result = radio.testConnection();
|
||||||
|
Serial.println(result,DEC);
|
||||||
|
radio.initialize();
|
||||||
|
radio.setFrequency(446000);
|
||||||
|
radio.setVolume1(0xF);
|
||||||
|
radio.setVolume2(0xF);
|
||||||
|
radio.setModeReceive();
|
||||||
|
radio.setTxSourceMic();
|
||||||
|
radio.setSQLoThresh(80);
|
||||||
|
radio.setSQOn();
|
||||||
|
Serial.println("Done with radio beacon setup. Press and hold a key to transmit.");
|
||||||
|
}
|
||||||
|
|
||||||
|
int state = 0;
|
||||||
|
long timer = 0;
|
||||||
|
int morseletter = 0;
|
||||||
|
int morsesymbol = 0;
|
||||||
|
long keyer = 0;
|
||||||
|
char symbol;
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
if(Serial.available() > 0) {
|
||||||
|
if(state == 0) {
|
||||||
|
state = 10;
|
||||||
|
radio.setModeTransmit();
|
||||||
|
timer = millis();
|
||||||
|
keyer = millis();
|
||||||
|
}
|
||||||
|
if(state == 10) {
|
||||||
|
timer = millis();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(millis() > (timer + 500)) { radio.setModeReceive(); morseletter = 0; morsesymbol = 0; state = 0; }
|
||||||
|
if(state == 10) {
|
||||||
|
if(millis() > (keyer + (DOT * 3))) {
|
||||||
|
keyer = millis();
|
||||||
|
symbol = lookup(callsign[morseletter],morsesymbol);
|
||||||
|
if(symbol == '-') { tone(9,1000,DOT*3); }
|
||||||
|
if(symbol == '.') { tone(9,1000,DOT); }
|
||||||
|
if(symbol == 0) { morsesymbol = 0; morseletter++; }
|
||||||
|
if(callsign[morseletter] == 0) { morsesymbol = 0; morseletter = 0; }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
char lookup(char letter, int morsesymbol) {
|
||||||
|
for(int x = 0; x < 54; x++) {
|
||||||
|
if(letter == bascii[x]) {
|
||||||
|
return bitu[x][morsesymbol];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,111 @@
|
||||||
|
/*
|
||||||
|
|
||||||
|
Record sound and then plays it back a few times.
|
||||||
|
Very low sound quality @ 2KHz 0.75 seconds
|
||||||
|
A bit robotic and weird
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
#define RATE 500
|
||||||
|
#define SIZE 1500
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
char sound[SIZE];
|
||||||
|
unsigned int sample1;
|
||||||
|
int x = -1;
|
||||||
|
int16_t rssi;
|
||||||
|
byte mode = 8;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Wire.begin();
|
||||||
|
// int result = radio.testConnection();
|
||||||
|
radio.initialize();
|
||||||
|
radio.setFrequency(446000);
|
||||||
|
setPwmFrequency(9, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
rssi = radio.readRSSI();
|
||||||
|
if(rssi > -100) {
|
||||||
|
if(x == -1) {
|
||||||
|
for(x = 0; x < SIZE; x++) {
|
||||||
|
if(mode == 4) {
|
||||||
|
sample1 = analogRead(0);
|
||||||
|
sound[x] = sample1 >> 4;
|
||||||
|
delayMicroseconds(RATE); x++;
|
||||||
|
sample1 = analogRead(0);
|
||||||
|
sound[x] = (sample1 & 0xF0) | sound[x];
|
||||||
|
delayMicroseconds(RATE);
|
||||||
|
} else {
|
||||||
|
sound[x] = analogRead(0);
|
||||||
|
delayMicroseconds(RATE); x++;
|
||||||
|
sound[x] = analogRead(0);
|
||||||
|
delayMicroseconds(RATE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(rssi < -100) {
|
||||||
|
if(x == 1500) {
|
||||||
|
radio.setModeTransmit();
|
||||||
|
delay(500);
|
||||||
|
tone(9,1000,500); delay(750);
|
||||||
|
for(int r = 0; r < 10; r++) {
|
||||||
|
for(x = 0; x < SIZE; x++) {
|
||||||
|
if(mode == 4) {
|
||||||
|
|
||||||
|
analogWrite(9,sound[x] << 4);
|
||||||
|
delayMicroseconds(RATE); x++;
|
||||||
|
analogWrite(9,sound[x] & 0xF);
|
||||||
|
delayMicroseconds(RATE); } else {
|
||||||
|
|
||||||
|
analogWrite(9,sound[x]);
|
||||||
|
delayMicroseconds(RATE); x++;
|
||||||
|
analogWrite(9,sound[x]);
|
||||||
|
delayMicroseconds(RATE);
|
||||||
|
}
|
||||||
|
} }
|
||||||
|
tone(9,1000,500); delay(750);
|
||||||
|
radio.setModeReceive();
|
||||||
|
x = -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setPwmFrequency(int pin, int divisor) {
|
||||||
|
byte mode;
|
||||||
|
if(pin == 5 || pin == 6 || pin == 9 || pin == 10) {
|
||||||
|
switch(divisor) {
|
||||||
|
case 1: mode = 0x01; break;
|
||||||
|
case 8: mode = 0x02; break;
|
||||||
|
case 64: mode = 0x03; break;
|
||||||
|
case 256: mode = 0x04; break;
|
||||||
|
case 1024: mode = 0x05; break;
|
||||||
|
default: return;
|
||||||
|
}
|
||||||
|
if(pin == 5 || pin == 6) {
|
||||||
|
TCCR0B = TCCR0B & 0b11111000 | mode;
|
||||||
|
} else {
|
||||||
|
TCCR1B = TCCR1B & 0b11111000 | mode;
|
||||||
|
}
|
||||||
|
} else if(pin == 3 || pin == 11) {
|
||||||
|
switch(divisor) {
|
||||||
|
case 1: mode = 0x01; break;
|
||||||
|
case 8: mode = 0x02; break;
|
||||||
|
case 32: mode = 0x03; break;
|
||||||
|
case 64: mode = 0x04; break;
|
||||||
|
case 128: mode = 0x05; break;
|
||||||
|
case 256: mode = 0x06; break;
|
||||||
|
case 1024: mode = 0x7; break;
|
||||||
|
default: return;
|
||||||
|
}
|
||||||
|
TCCR2B = TCCR2B & 0b11111000 | mode;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -0,0 +1,45 @@
|
||||||
|
/*
|
||||||
|
|
||||||
|
Sends an SSTV test pattern
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define DOT 100
|
||||||
|
#define CALLSIGN "1ZZ9ZZ/B"
|
||||||
|
|
||||||
|
/* Standard libraries and variable init */
|
||||||
|
|
||||||
|
#include <HAMShield.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
int16_t rssi;
|
||||||
|
|
||||||
|
/* get our radio ready */
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Wire.begin();
|
||||||
|
Serial.begin(9600);
|
||||||
|
Serial.print("Radio status: ");
|
||||||
|
int result = radio.testConnection();
|
||||||
|
Serial.println(result);
|
||||||
|
radio.initialize();
|
||||||
|
radio.setFrequency(446000);
|
||||||
|
radio.setModeReceive();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* main program loop */
|
||||||
|
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
if(radio.waitForChannel(1000,2000)) { // Wait forever for calling frequency to open, then wait 2 seconds for breakers
|
||||||
|
radio.setModeTransmit(); // Turn on the transmitter
|
||||||
|
delay(250); // Wait a moment
|
||||||
|
radio.SSTVTestPattern(MARTIN1); // send a MARTIN1 test pattern
|
||||||
|
delay(250);
|
||||||
|
radio.setModeReceive(); // Turn off the transmitter
|
||||||
|
} else { delay(30000); } // someone broke in fast after prior transmission, was it an emergency? wait 30 secs.
|
||||||
|
|
||||||
|
delay(60000); // Wait a minute
|
||||||
|
}
|
||||||
|
|
|
@ -0,0 +1,203 @@
|
||||||
|
/*
|
||||||
|
|
||||||
|
SerialTransceiver is TTL Serial port "glue" to allow desktop or laptop control of the HAMShield
|
||||||
|
|
||||||
|
Commands:
|
||||||
|
|
||||||
|
Mode ASCII Description Implemented
|
||||||
|
-------------- ----------- -------------------------------------------------------------------------------------------------------------------------------------------- -----------------
|
||||||
|
Transmit space Space must be received at least every 500 mS Yes
|
||||||
|
Receive not space If space is not received and/or 500 mS timeout of space occurs, unit will go into receive mode Yes
|
||||||
|
CTCSS In A<tone>; <tone> must be a numerical ascii value with decimal point indicating CTCSS receive tone required to unsquelch No
|
||||||
|
CTCSS Out B<tone>; <tone> must be a numerical ascii value with decimal point indicating CTCSS transmit tone No
|
||||||
|
CTCSS Enable C<state>; Turns on CTCSS mode (analog tone) with 1, off with 0. No
|
||||||
|
CDCSS Enable D<state>; Turns on CDCSS mode (digital tone) with 1, off with 0. No
|
||||||
|
Bandwidth E<mode>; for 12.5KHz mode is 0, for 25KHz, mode is 1 No
|
||||||
|
Frequency F<freq>; Set the receive frequency in KHz, if offset is disabled, this is the transmit frequency No
|
||||||
|
CDCSS In G<code>; <code> must be a valid CDCSS code No
|
||||||
|
CDCSS Out H<code>; <code> must be a valid CDCSS code No
|
||||||
|
Print tones I Prints out all configured tones and codes, coma delimited in format: CTCSS In, CTCSS Out, CDCSS In, CDCSS Out No
|
||||||
|
Power level P<level>; Set the power amp level, 0 = lowest, 255 = highest No
|
||||||
|
Enable Offset R<state>; 1 turns on repeater offset mode, 0 turns off repeater offset mode No
|
||||||
|
Squelch S<level>; Set the squelch level No
|
||||||
|
TX Offset T<freq>; The absolute frequency of the repeater offset to transmit on in KHz No
|
||||||
|
Volume V<level>; Set the volume level of the receiver No
|
||||||
|
Reset X Reset all settings to default No
|
||||||
|
Sleep Z Sleep radio No
|
||||||
|
Filters @<state>; Set bit to enable, clear bit to disable: 0 = pre/de-emphasis, 1 = high pass filter, 2 = low pass filter (default: ascii 7, all enabled) No
|
||||||
|
Vox mode $<state>; 0 = vox off, >= 1 audio sensitivity. lower value more sensitive No
|
||||||
|
Mic Channel *<state>; Set the voice channel. 0 = signal from mic or arduino, 1 = internal tone generator No
|
||||||
|
RSSI ? Respond with the current receive level in - dBm (no sign provided on numerical response) No
|
||||||
|
Tone Gen % (notes) To send a tone, use the following format: Single tone: %1,<freq>,<length>; Dual tone: %2,<freq>,<freq>,<length>; DTMF: %3,<key>,<length>; No
|
||||||
|
Voice Level ^ Respond with the current voice level (VSSI)
|
||||||
|
|
||||||
|
|
||||||
|
Responses:
|
||||||
|
|
||||||
|
Condition ASCII Description
|
||||||
|
------------ ---------- -----------------------------------------------------------------
|
||||||
|
Startup *<code>; Startup and shield connection status
|
||||||
|
Success !; Generic success message for command that returns no value
|
||||||
|
Error X<code>; Indicates an error code. The numerical value is the type of error
|
||||||
|
Value :<value>; In response to a query
|
||||||
|
Status #<value>; Unsolicited status message
|
||||||
|
Debug Msg @<text>; 32 character debug message
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "Wire.h"
|
||||||
|
#include "HAMShield.h"
|
||||||
|
|
||||||
|
int state;
|
||||||
|
int txcount = 0;
|
||||||
|
long timer = 0;
|
||||||
|
long freq = 144390;
|
||||||
|
long tx = 0;
|
||||||
|
char cmdbuff[32] = "";
|
||||||
|
int temp = 0;
|
||||||
|
int repeater = 0;
|
||||||
|
float ctcssin = 0;
|
||||||
|
float ctcssout = 0;
|
||||||
|
int cdcssin = 0;
|
||||||
|
int cdcssout = 0;
|
||||||
|
|
||||||
|
|
||||||
|
HAMShield radio;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
Serial.print(";;;;;;;;;;;;;;;;;;;;;;;;;;");
|
||||||
|
Wire.begin();
|
||||||
|
int result = radio.testConnection();
|
||||||
|
Serial.print("*");
|
||||||
|
Serial.print(result,DEC);
|
||||||
|
Serial.print(";");
|
||||||
|
radio.initialize(); // initializes automatically for UHF 12.5kHz channel
|
||||||
|
Serial.print("*START;");
|
||||||
|
radio.frequency(freq);
|
||||||
|
radio.setVolume1(0xF);
|
||||||
|
radio.setVolume2(0xF);
|
||||||
|
radio.setModeReceive();
|
||||||
|
radio.setTxSourceMic();
|
||||||
|
radio.setRfPower(255); // 30 is 0.5V, which corresponds to 29 dBm out (see RF6886 datasheet)
|
||||||
|
radio.setSQLoThresh(80);
|
||||||
|
radio.setSQOn();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
if(Serial.available()) {
|
||||||
|
|
||||||
|
int text = Serial.read();
|
||||||
|
|
||||||
|
switch (state) {
|
||||||
|
|
||||||
|
case 10:
|
||||||
|
if(text == 32) { timer = millis();}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 0:
|
||||||
|
switch(text) {
|
||||||
|
|
||||||
|
case 32: // space - transmit
|
||||||
|
if(repeater == 1) { radio.frequency(tx); }
|
||||||
|
radio.setRX(0);
|
||||||
|
radio.setTX(1);
|
||||||
|
state = 10;
|
||||||
|
Serial.print("#TX,ON;");
|
||||||
|
timer = millis();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 63: // ? - RSSI
|
||||||
|
Serial.print(":");
|
||||||
|
Serial.print(radio.readRSSI(),DEC);
|
||||||
|
Serial.print(";");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 65: // A - CTCSS In
|
||||||
|
getValue();
|
||||||
|
ctcssin = atof(cmdbuff);
|
||||||
|
radio.setCtcss(ctcssin);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 66: // B - CTCSS Out
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 67: // C - CTCSS Enable
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 68: // D - CDCSS Enable
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 70: // F - frequency
|
||||||
|
getValue();
|
||||||
|
freq = atol(cmdbuff);
|
||||||
|
if(radio.frequency(freq) == true) { Serial.print("@"); Serial.print(freq,DEC); Serial.print(";!;"); } else { Serial.print("X1;"); }
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 80: // P - power level
|
||||||
|
getValue();
|
||||||
|
temp = atol(cmdbuff);
|
||||||
|
radio.setRfPower(temp);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 82: // R - repeater offset mode
|
||||||
|
getValue();
|
||||||
|
temp = atol(cmdbuff);
|
||||||
|
if(temp == 0) { repeater = 0; }
|
||||||
|
if(temp == 1) { repeater = 1; }
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 83: // S - squelch
|
||||||
|
getValue();
|
||||||
|
temp = atol(cmdbuff);
|
||||||
|
radio.setSQLoThresh(temp);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 84: // T - transmit offset
|
||||||
|
getValue();
|
||||||
|
tx = atol(cmdbuff);
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
|
case 94: // ^ - VSSI (voice) level
|
||||||
|
Serial.print(":");
|
||||||
|
Serial.print(radio.readVSSI(),DEC);
|
||||||
|
Serial.print(";");
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
if(state == 10) {
|
||||||
|
if(millis() > (timer + 500)) { Serial.print("#TX,OFF;");radio.setRX(1); radio.setTX(0); if(repeater == 1) { radio.frequency(freq); } state = 0; txcount = 0; }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void getValue() {
|
||||||
|
int p = 0;
|
||||||
|
char temp;
|
||||||
|
for(;;) {
|
||||||
|
if(Serial.available()) {
|
||||||
|
temp = Serial.read();
|
||||||
|
if(temp == 59) { cmdbuff[p] = 0; Serial.print("@");
|
||||||
|
for(int x = 0; x < 32; x++) { Serial.print(cmdbuff[x]); }
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
cmdbuff[p] = temp;
|
||||||
|
p++;
|
||||||
|
if(p == 32) {
|
||||||
|
Serial.print("@");
|
||||||
|
for(int x = 0; x < 32; x++) {
|
||||||
|
Serial.print(cmdbuff[x]);
|
||||||
|
}
|
||||||
|
|
||||||
|
cmdbuff[0] = 0;
|
||||||
|
|
||||||
|
Serial.print("X0;"); return; } // some sort of alignment issue? lets not feed junk into whatever takes this string in
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
File diff suppressed because one or more lines are too long
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,30 @@
|
||||||
|
#######################################
|
||||||
|
# Syntax Coloring Map HAMShield
|
||||||
|
#######################################
|
||||||
|
|
||||||
|
#######################################
|
||||||
|
# Datatypes (KEYWORD1)
|
||||||
|
#######################################
|
||||||
|
|
||||||
|
#SD KEYWORD1
|
||||||
|
#File KEYWORD1
|
||||||
|
|
||||||
|
#######################################
|
||||||
|
# Methods and Functions (KEYWORD2)
|
||||||
|
#######################################
|
||||||
|
#begin KEYWORD2
|
||||||
|
#exists KEYWORD2
|
||||||
|
#mkdir KEYWORD2
|
||||||
|
#remove KEYWORD2
|
||||||
|
#rmdir KEYWORD2
|
||||||
|
#open KEYWORD2
|
||||||
|
#close KEYWORD2
|
||||||
|
#seek KEYWORD2
|
||||||
|
#position KEYWORD2
|
||||||
|
#size KEYWORD2
|
||||||
|
|
||||||
|
#######################################
|
||||||
|
# Constants (LITERAL1)
|
||||||
|
#######################################
|
||||||
|
#FILE_READ LITERAL1
|
||||||
|
#FILE_WRITE LITERAL1
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,554 @@
|
||||||
|
// HAMShield library collection
|
||||||
|
// Based on Programming Manual rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
|
||||||
|
// 11/22/2013 by Morgan Redfield <redfieldm@gmail.com>
|
||||||
|
// 04/26/2015 various changes Casey Halverson <spaceneedle@gmail.com>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef _HAMSHIELD_H_
|
||||||
|
#define _HAMSHIELD_H_
|
||||||
|
|
||||||
|
#include "I2Cdev_rda.h"
|
||||||
|
#include <avr/pgmspace.h>
|
||||||
|
|
||||||
|
// HAMShield constants
|
||||||
|
|
||||||
|
#define HAMSHIELD_MORSE_DOT 100 // Morse code dot length (smaller is faster WPM)
|
||||||
|
#define HAMSHIELD_MORSE_BUFFER_SIZE 80 // Char buffer size for morse code text
|
||||||
|
#define HAMSHIELD_AUX_BUTTON 5 // Pin assignment for AUX button
|
||||||
|
#define HAMSHIELD_PWM_PIN 9 // Pin assignment for PWM output
|
||||||
|
#define HAMSHIELD_EMPTY_CHANNEL_RSSI -110 // Threshold where channel is considered "clear"
|
||||||
|
|
||||||
|
// button modes
|
||||||
|
#define PTT_MODE 1
|
||||||
|
#define RESET_MODE 2
|
||||||
|
|
||||||
|
// Device Constants
|
||||||
|
#define A1846S_DEV_ADDR_SENHIGH 0b0101110
|
||||||
|
#define A1846S_DEV_ADDR_SENLOW 0b1110001
|
||||||
|
|
||||||
|
|
||||||
|
// Device Registers
|
||||||
|
#define A1846S_CTL_REG 0x30 // control register
|
||||||
|
#define A1846S_CLK_MODE_REG 0x04 // clk_mode
|
||||||
|
#define A1846S_PABIAS_REG 0x0A // control register for bias voltage
|
||||||
|
#define A1846S_BAND_SEL_REG 0x0F // band_sel register <1:0>
|
||||||
|
#define A1846S_GPIO_MODE_REG 0x1F // GPIO mode select register
|
||||||
|
#define A1846S_FREQ_HI_REG 0x29 // freq<29:16>
|
||||||
|
#define A1846S_FREQ_LO_REG 0x2A // freq<15:0>
|
||||||
|
#define A1846S_XTAL_FREQ_REG 0x2B // xtal_freq<15:0>
|
||||||
|
#define A1846S_ADCLK_FREQ_REG 0x2C // adclk_freq<15:0>
|
||||||
|
#define A1846S_INT_MODE_REG 0x2D // interrupt enables
|
||||||
|
#define A1846S_TX_VOICE_REG 0x3C // tx voice control reg
|
||||||
|
#define A1846S_TH_H_VOX_REG 0x41 // register holds vox high (open) threshold bits
|
||||||
|
#define A1846S_TH_L_VOX_REG 0x42 // register holds vox low (shut) threshold bits
|
||||||
|
#define A1846S_FM_DEV_REG 0x43 // register holds fm deviation settings
|
||||||
|
#define A1846S_RX_VOLUME_REG 0x44 // register holds RX volume settings
|
||||||
|
#define A1846S_SUBAUDIO_REG 0x45 // sub audio register
|
||||||
|
#define A1846S_SQ_OPEN_THRESH_REG 0x48 // see sq
|
||||||
|
#define A1846S_SQ_SHUT_THRESH_REG 0x49 // see sq
|
||||||
|
#define A1846S_CTCSS_FREQ_REG 0x4A // ctcss_freq<15:0>
|
||||||
|
#define A1846S_CDCSS_CODE_HI_REG 0x4B // cdcss_code<23:16>
|
||||||
|
#define A1846S_CDCSS_CODE_LO_REG 0x4C // cdccs_code<15:0>
|
||||||
|
#define A1846S_SQ_OUT_SEL_REG 0x54 // see sq
|
||||||
|
#define A1846S_EMPH_FILTER_REG 0x58
|
||||||
|
#define A1846S_FLAG_REG 0x5C // holds flags for different statuses
|
||||||
|
#define A1846S_RSSI_REG 0x5F // holds RSSI (unit 1/8dB)
|
||||||
|
#define A1846S_VSSI_REG 0x60 // holds VSSI (unit mV)
|
||||||
|
#define A1846S_DTMF_CTL_REG 0x63 // see dtmf
|
||||||
|
#define A1846S_DTMF_C01_REG 0x66 // holds frequency value for c0 and c1
|
||||||
|
#define A1846S_DTMF_C23_REG 0x67 // holds frequency value for c2 and c3
|
||||||
|
#define A1846S_DTMF_C45_REG 0x68 // holds frequency value for c4 and c5
|
||||||
|
#define A1846S_DTMF_C67_REG 0x69 // holds frequency value for c6 and c7
|
||||||
|
#define A1846S_DTMF_RX_REG 0x6C // received dtmf signal
|
||||||
|
|
||||||
|
// NOTE: could add registers and bitfields for dtmf tones, is this necessary?
|
||||||
|
|
||||||
|
|
||||||
|
// Device Bit Fields
|
||||||
|
|
||||||
|
// Bitfields for A1846S_CTL_REG
|
||||||
|
#define A1846S_CHAN_MODE_BIT 13 //channel_mode<1:0>
|
||||||
|
#define A1846S_CHAN_MODE_LENGTH 2
|
||||||
|
#define A1846S_TAIL_ELIM_EN_BIT 11 // enables tail elim when set to 1
|
||||||
|
#define A1846S_ST_MODE_BIT 9 // set mode for txon and rxon
|
||||||
|
#define A1846S_ST_MODE_LENGTH 2
|
||||||
|
#define A1846S_MUTE_BIT 7 // 0 no mute, 1 mute when rxno
|
||||||
|
#define A1846S_TX_MODE_BIT 6 //tx-on
|
||||||
|
#define A1846S_RX_MODE_BIT 5 //rx-on
|
||||||
|
#define A1846S_VOX_ON_BIT 4 // 0 off, 1 on and chip auto-vox
|
||||||
|
#define A1846S_SQ_ON_BIT 3 // auto sq enable bit
|
||||||
|
#define A1846S_PWR_DWN_BIT 2 // power control bit
|
||||||
|
#define A1846S_CHIP_CAL_EN_BIT 1 // 0 cal disable, 1 cal enable
|
||||||
|
#define A1846S_SOFT_RESET_BIT 0 // 0 normal value, 1 reset all registers to normal value
|
||||||
|
|
||||||
|
// Bitfields for A1846S_CLK_MODE_REG
|
||||||
|
#define A1846S_CLK_MODE_BIT 0 // 0 24-28MHz, 1 12-14MHz
|
||||||
|
|
||||||
|
// Bitfields for A1846S_PABIAS_REG
|
||||||
|
#define A1846S_PABIAS_BIT 5 // pabias_voltage<5:0>
|
||||||
|
#define A1846S_PABIAS_LENGTH 6
|
||||||
|
|
||||||
|
// Bitfields for A1846S_BAND_SEL_REG
|
||||||
|
#define A1846S_BAND_SEL_BIT 7 // band_sel<1:0>
|
||||||
|
#define A1846S_BAND_SEL_LENGTH 2
|
||||||
|
|
||||||
|
// Bitfields for RDA1864_GPIO_MODE_REG
|
||||||
|
#define RDA1864_GPIO7_MODE_BIT 15 // <1:0> 00=hi-z,01=vox,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO7_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO6_MODE_BIT 13 // <1:0> 00=hi-z,01=sq or =sq&ctcss/cdcss when sq_out_sel=1,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO6_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO5_MODE_BIT 11 // <1:0> 00=hi-z,01=txon_rf,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO5_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO4_MODE_BIT 9 // <1:0> 00=hi-z,01=rxon_rf,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO4_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO3_MODE_BIT 7 // <1:0> 00=hi-z,01=sdo,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO3_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO2_MODE_BIT 5 // <1:0> 00=hi-z,01=int,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO2_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO1_MODE_BIT 3 // <1:0> 00=hi-z,01=code_out/code_in,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO1_MODE_LENGTH 2
|
||||||
|
#define RDA1864_GPIO0_MODE_BIT 1 // <1:0> 00=hi-z,01=css_out/css_in/css_cmp,10=low,11=hi
|
||||||
|
#define RDA1864_GPIO0_MODE_LENGTH 2
|
||||||
|
|
||||||
|
// Bitfields for A1846S_INT_MODE_REG
|
||||||
|
#define A1846S_CSS_CMP_INT_BIT 9 // css_cmp_uint16_t enable
|
||||||
|
#define A1846S_RXON_RF_INT_BIT 8 // rxon_rf_uint16_t enable
|
||||||
|
#define A1846S_TXON_RF_INT_BIT 7 // txon_rf_uint16_t enable
|
||||||
|
#define A1846S_DTMF_IDLE_INT_BIT 6 // dtmf_idle_uint16_t enable
|
||||||
|
#define A1846S_CTCSS_PHASE_INT_BIT 5 // ctcss phase shift detect uint16_t enable
|
||||||
|
#define A1846S_IDLE_TIMEOUT_INT_BIT 4 // idle state time out uint16_t enable
|
||||||
|
#define A1846S_RXON_RF_TIMeOUT_INT_BIT 3 // rxon_rf timerout uint16_t enable
|
||||||
|
#define A1846S_SQ_INT_BIT 2 // sq uint16_t enable
|
||||||
|
#define A1846S_TXON_RF_TIMEOUT_INT_BIT 1 // txon_rf time out uint16_t enable
|
||||||
|
#define A1846S_VOX_INT_BIT 0 // vox uint16_t enable
|
||||||
|
|
||||||
|
// Bitfields for A1846S_TX_VOICE_REG
|
||||||
|
#define A1846S_VOICE_SEL_BIT 15 //voice_sel<1:0>
|
||||||
|
#define A1846S_VOICE_SEL_LENGTH 2
|
||||||
|
|
||||||
|
// Bitfields for A1846S_TH_H_VOX_REG
|
||||||
|
#define A1846S_TH_H_VOX_BIT 14 // th_h_vox<14:0>
|
||||||
|
#define A1846S_TH_H_VOX_LENGTH 15
|
||||||
|
|
||||||
|
// Bitfields for A1846S_FM_DEV_REG
|
||||||
|
#define A1846S_FM_DEV_VOICE_BIT 12 // CTCSS/CDCSS and voice deviation <6:0>
|
||||||
|
#define A1846S_FM_DEV_VOICE_LENGTH 7
|
||||||
|
#define A1846S_FM_DEV_CSS_BIT 5 // CTCSS/CDCSS deviation only <5:0>
|
||||||
|
#define A1846S_FM_DEV_CSS_LENGTH 6
|
||||||
|
|
||||||
|
// Bitfields for A1846S_RX_VOLUME_REG
|
||||||
|
#define A1846S_RX_VOL_1_BIT 7 // volume 1 <3:0>, (0000)-15dB~(1111)0dB, step 1dB
|
||||||
|
#define A1846S_RX_VOL_1_LENGTH 4
|
||||||
|
#define A1846S_RX_VOL_2_BIT 3 // volume 2 <3:0>, (0000)-15dB~(1111)0dB, step 1dB
|
||||||
|
#define A1846S_RX_VOL_2_LENGTH 4
|
||||||
|
|
||||||
|
// Bitfields for A1846S_SUBAUDIO_REG Sub Audio Register
|
||||||
|
#define A1846S_SHIFT_SEL_BIT 15 // shift_sel<1:0> see eliminating tail noise
|
||||||
|
#define A1846S_SHIFT_SEL_LENGTH 2
|
||||||
|
#define A1846S_POS_DET_EN_BIT 11 // if 1, cdcss code will be detected
|
||||||
|
#define A1846S_CSS_DET_EN_BIT 10 // 1 - sq detect will add ctcss/cdcss detect result and control voice output on or off
|
||||||
|
#define A1846S_NEG_DET_EN_BIT 7 // if 1, cdcss inverse code will be detected at same time
|
||||||
|
#define A1846S_CDCSS_SEL_BIT 4 // cdcss_sel
|
||||||
|
#define A1846S_CTCSS_SEL_BIT 3 // ctcss_sel
|
||||||
|
#define A1846S_C_MODE_BIT 2 // c_mode<2:0>
|
||||||
|
#define A1846S_C_MODE_LENGTH 3
|
||||||
|
|
||||||
|
// Bitfields for A1846S_SQ_THRESH_REG
|
||||||
|
#define A1846S_SQ_OPEN_THRESH_BIT 9 // sq open threshold <9:0>
|
||||||
|
#define A1846S_SQ_OPEN_THRESH_LENGTH 10
|
||||||
|
|
||||||
|
// Bitfields for A1846S_SQ_SHUT_THRESH_REG
|
||||||
|
#define A1846S_SQ_SHUT_THRESH_BIT 9 // sq shut threshold <9:0>
|
||||||
|
#define A1846S_SQ_SHUT_THRESH_LENGTH 10
|
||||||
|
|
||||||
|
// Bitfields for A1846S_SQ_OUT_SEL_REG
|
||||||
|
#define A1846S_SQ_OUT_SEL_BIT 7 // sq_out_sel
|
||||||
|
|
||||||
|
// Bitfields for A1846S_EMPH_FILTER_REG
|
||||||
|
#define A1846S_EMPH_FILTER_EN 3
|
||||||
|
|
||||||
|
// Bitfields for A1846S_FLAG_REG
|
||||||
|
#define A1846S_DTMF_IDLE_FLAG_BIT 12 // dtmf idle flag
|
||||||
|
#define A1846S_RXON_RF_FLAG_BIT 10 // 1 when rxon is enabled
|
||||||
|
#define A1846S_TXON_RF_FLAG_BIT 9 // 1 when txon is enabled
|
||||||
|
#define A1846S_INVERT_DET_FLAG_BIT 7 // ctcss phase shift detect
|
||||||
|
#define A1846S_CSS_CMP_FLAG_BIT 2 // ctcss/cdcss compared
|
||||||
|
#define A1846S_SQ_FLAG_BIT 1 // sq final signal out from dsp
|
||||||
|
#define A1846S_VOX_FLAG_BIT 0 // vox out from dsp
|
||||||
|
|
||||||
|
// Bitfields for A1846S_RSSI_REG
|
||||||
|
#define A1846S_RSSI_BIT 9 // RSSI readings <9:0>
|
||||||
|
#define A1846S_RSSI_LENGTH 10
|
||||||
|
|
||||||
|
// Bitfields for A1846S_VSSI_REG
|
||||||
|
#define A1846S_VSSI_BIT 14 // voice signal strength indicator <14:0> (unit mV)
|
||||||
|
#define A1846S_VSSI_LENGTH 15
|
||||||
|
|
||||||
|
// Bitfields for A1846S_DTMF_CTL_REG
|
||||||
|
#define A1846S_DTMF_MODE_BIT 9 //
|
||||||
|
#define A1846S_DTMF_MODE_LENGTH 2
|
||||||
|
#define A1846S_DTMF_EN_BIT 8 // enable dtmf
|
||||||
|
#define A1846S_DTMF_TIME1_BIT 7 // dtmf time 1 <3:0>
|
||||||
|
#define A1846S_DTMF_TIME1_LENGTH 4
|
||||||
|
#define A1846S_DTMF_TIME2_BIT 3 // dtmf time 2 <3:0>
|
||||||
|
#define A1846S_DTMF_TIME2_LENGTH 4
|
||||||
|
|
||||||
|
// Bitfields for A1846S_DTMF_RX_REG
|
||||||
|
#define A1846S_DTMF_INDEX_BIT 10 // dtmf index <5:3> - tone 1 detect index, <2:0> - tone 2 detect index
|
||||||
|
#define A1846S_DTMF_INDEX_LENGTH 6
|
||||||
|
#define A1846S_DTMF_TONE1_IND_BIT 10
|
||||||
|
#define A1846S_DTMF_TONE1_IND_LENGTH 3
|
||||||
|
#define A1846S_DTMF_TONE2_IND_BIT 7
|
||||||
|
#define A1846S_DTMF_TONE2_IND_LENGTH 3
|
||||||
|
#define A1846S_DTMF_FLAG_BIT 4
|
||||||
|
#define A1846S_DTMF_CODE_BIT 3 // dtmf code out <3:0>
|
||||||
|
#define A1846S_DTMF_CODE_LENGTH 4
|
||||||
|
// dtmf code out
|
||||||
|
// 1:f0+f4, 2:f0+f5, 3:f0+f6, A:f0+f7,
|
||||||
|
// 4:f1+f4, 5:f1+f5, 6:f1+f6, B:f1+f7,
|
||||||
|
// 7:f2+f4, 8:f2+f5, 9:f2+f6, C:f2+f7,
|
||||||
|
// E(*):f3+f4, 0:f3+f5, F(#):f3+f6, D:f3+f7
|
||||||
|
|
||||||
|
// Bitfields for DTMF registers
|
||||||
|
#define A1846S_DTMF_C0_BIT 15
|
||||||
|
#define A1846S_DTMF_C0_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C1_BIT 7
|
||||||
|
#define A1846S_DTMF_C1_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C2_BIT 15
|
||||||
|
#define A1846S_DTMF_C2_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C3_BIT 7
|
||||||
|
#define A1846S_DTMF_C3_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C4_BIT 15
|
||||||
|
#define A1846S_DTMF_C4_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C5_BIT 7
|
||||||
|
#define A1846S_DTMF_C5_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C6_BIT 15
|
||||||
|
#define A1846S_DTMF_C6_LENGTH 8
|
||||||
|
#define A1846S_DTMF_C7_BIT 7
|
||||||
|
#define A1846S_DTMF_C7_LENGTH 8
|
||||||
|
|
||||||
|
// SSTV VIS Codes
|
||||||
|
|
||||||
|
|
||||||
|
#define ROBOT8BW 2
|
||||||
|
#define SC2-180 55
|
||||||
|
#define MARTIN1 44
|
||||||
|
|
||||||
|
// RTTY Frequencies
|
||||||
|
|
||||||
|
#define HAMSHIELD_RTTY_FREQ 2200
|
||||||
|
#define HAMSHIELD_RTTY_SHIFT 850
|
||||||
|
#define HAMSHIELD_RTTY_BAUD 75
|
||||||
|
|
||||||
|
// PSK31 Frequencies
|
||||||
|
|
||||||
|
#define HAMSHIELD_PSK31_FREQ 1000
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
class HAMShield {
|
||||||
|
public:
|
||||||
|
HAMShield();
|
||||||
|
HAMShield(uint8_t address);
|
||||||
|
|
||||||
|
void initialize();
|
||||||
|
bool testConnection();
|
||||||
|
|
||||||
|
// read control reg
|
||||||
|
uint16_t readCtlReg();
|
||||||
|
void softReset();
|
||||||
|
|
||||||
|
// center frequency
|
||||||
|
void setFrequency(uint32_t freq_khz);
|
||||||
|
uint32_t getFrequency();
|
||||||
|
|
||||||
|
// band
|
||||||
|
// 00 - 400-520MHz
|
||||||
|
// 10 - 200-260MHz
|
||||||
|
// 11 - 134-174MHz
|
||||||
|
void setBand(uint16_t band);
|
||||||
|
uint16_t getBand();
|
||||||
|
|
||||||
|
void setUHF();
|
||||||
|
void setVHF();
|
||||||
|
void setNoFilters();
|
||||||
|
bool frequency(uint32_t freq_khz);
|
||||||
|
|
||||||
|
// xtal frequency (kHz)
|
||||||
|
// 12-14MHz crystal: this reg is set to crystal freq_khz
|
||||||
|
// 24-28MHz crystal: this reg is set to crystal freq_khz / 2
|
||||||
|
void setXtalFreq(uint16_t freq_kHz);
|
||||||
|
uint16_t getXtalFreq();
|
||||||
|
|
||||||
|
// adclk frequency (kHz)
|
||||||
|
// 12-14MHz crystal: this reg is set to crystal freq_khz / 2
|
||||||
|
// 24-28MHz crystal: this reg is set to crystal freq_khz / 4
|
||||||
|
void setAdcClkFreq(uint16_t freq_kHz);
|
||||||
|
uint16_t getAdcClkFreq();
|
||||||
|
|
||||||
|
// clk mode
|
||||||
|
// 12-14MHz: set to 1
|
||||||
|
// 24-28MHz: set to 0
|
||||||
|
void setClkMode(bool LFClk);
|
||||||
|
bool getClkMode();
|
||||||
|
|
||||||
|
// clk example
|
||||||
|
// 12.8MHz clock
|
||||||
|
// A1846S_XTAL_FREQ_REG[15:0]= xtal_freq<15:0>=12.8*1000=12800
|
||||||
|
// A1846S_ADCLK_FREQ_REG[12:0] =adclk_freq<15:0>=(12.8/2)*1000=6400
|
||||||
|
// A1846S_CLK_MODE_REG[0]= clk_mode =1
|
||||||
|
|
||||||
|
// TX/RX control
|
||||||
|
|
||||||
|
// channel mode
|
||||||
|
// 11 - 25kHz channel
|
||||||
|
// 00 - 12.5kHz channel
|
||||||
|
// 10,01 - reserved
|
||||||
|
void setChanMode(uint16_t mode);
|
||||||
|
uint16_t getChanMode();
|
||||||
|
|
||||||
|
// choose tx or rx
|
||||||
|
void setTX(bool on_noff);
|
||||||
|
bool getTX();
|
||||||
|
|
||||||
|
void setRX(bool on_noff);
|
||||||
|
bool getRX();
|
||||||
|
|
||||||
|
void setModeTransmit(); // turn off rx, turn on tx
|
||||||
|
void setModeReceive(); // turn on rx, turn off tx
|
||||||
|
void setModeOff(); // turn off rx, turn off tx, set pwr_dwn bit
|
||||||
|
|
||||||
|
// set tx source
|
||||||
|
// 00 - Mic source
|
||||||
|
// 01 - sine source from tone2
|
||||||
|
// 10 - tx code from GPIO1 code_in (gpio1<1:0> must be set to 01)
|
||||||
|
// 11 - no tx source
|
||||||
|
void setTxSource(uint16_t tx_source);
|
||||||
|
void setTxSourceMic();
|
||||||
|
void setTxSourceSine();
|
||||||
|
void setTxSourceCode();
|
||||||
|
void setTxSourceNone();
|
||||||
|
uint16_t getTxSource();
|
||||||
|
|
||||||
|
// set PA_bias voltage
|
||||||
|
// 000000: 1.01V
|
||||||
|
// 000001:1.05V
|
||||||
|
// 000010:1.09V
|
||||||
|
// 000100: 1.18V
|
||||||
|
// 001000: 1.34V
|
||||||
|
// 010000: 1.68V
|
||||||
|
// 100000: 2.45V
|
||||||
|
// 1111111:3.13V
|
||||||
|
void setPABiasVoltage(uint16_t voltage);
|
||||||
|
uint16_t getPABiasVoltage();
|
||||||
|
|
||||||
|
// Subaudio settings
|
||||||
|
|
||||||
|
// Ctcss/cdcss mode sel
|
||||||
|
// x00=disable,
|
||||||
|
// 001=inner ctcss en,
|
||||||
|
// 010= inner cdcss en
|
||||||
|
// 101= outer ctcss en,
|
||||||
|
// 110=outer cdcss en
|
||||||
|
// others =disable
|
||||||
|
void setCtcssCdcssMode(uint16_t mode);
|
||||||
|
uint16_t getCtcssCdcssMode();
|
||||||
|
void setInnerCtcssMode();
|
||||||
|
void setInnerCdcssMode();
|
||||||
|
void setOuterCtcssMode();
|
||||||
|
void setOuterCdcssMode();
|
||||||
|
void disableCtcssCdcss();
|
||||||
|
|
||||||
|
// Ctcss_sel
|
||||||
|
// 1 = ctcss_cmp/cdcss_cmp out via gpio
|
||||||
|
// 0 = ctcss/cdcss sdo out vio gpio
|
||||||
|
void setCtcssSel(bool cmp_nsdo);
|
||||||
|
bool getCtcssSel();
|
||||||
|
|
||||||
|
// Cdcss_sel
|
||||||
|
// 1 = long (24 bit) code
|
||||||
|
// 0 = short(23 bit) code
|
||||||
|
void setCdcssSel(bool long_nshort);
|
||||||
|
bool getCdcssSel();
|
||||||
|
// Cdcss neg_det_en
|
||||||
|
void enableCdcssNegDet();
|
||||||
|
void disableCdcssNegDet();
|
||||||
|
bool getCdcssNegDetEnabled();
|
||||||
|
|
||||||
|
// Cdcss pos_det_en
|
||||||
|
void enableCdcssPosDet();
|
||||||
|
void disableCdcssPosDet();
|
||||||
|
bool getCdcssPosDetEnabled();
|
||||||
|
|
||||||
|
// css_det_en
|
||||||
|
void enableCssDet();
|
||||||
|
void disableCssDet();
|
||||||
|
bool getCssDetEnabled();
|
||||||
|
|
||||||
|
// ctcss freq
|
||||||
|
void setCtcss(float freq);
|
||||||
|
void setCtcssFreq(uint16_t freq);
|
||||||
|
uint16_t getCtcssFreq();
|
||||||
|
void setCtcssFreqToStandard(); // freq must be 134.4Hz for standard cdcss mode
|
||||||
|
|
||||||
|
// cdcss codes
|
||||||
|
void setCdcssCode(uint16_t code);
|
||||||
|
uint16_t getCdcssCode();
|
||||||
|
|
||||||
|
// SQ
|
||||||
|
void setSQOn();
|
||||||
|
void setSQOff();
|
||||||
|
bool getSQState();
|
||||||
|
|
||||||
|
// SQ threshold
|
||||||
|
void setSQHiThresh(uint16_t sq_hi_threshold); // Sq detect high th, rssi_cmp will be 1 when rssi>th_h_sq, unit 1/8dB
|
||||||
|
uint16_t getSQHiThresh();
|
||||||
|
void setSQLoThresh(uint16_t sq_lo_threshold); // Sq detect low th, rssi_cmp will be 0 when rssi<th_l_sq && time delay meet, unit 1/8 dB
|
||||||
|
uint16_t getSQLoThresh();
|
||||||
|
|
||||||
|
// SQ out select
|
||||||
|
void setSQOutSel();
|
||||||
|
void clearSQOutSel();
|
||||||
|
bool getSQOutSel();
|
||||||
|
|
||||||
|
// VOX
|
||||||
|
void setVoxOn();
|
||||||
|
void setVoxOff();
|
||||||
|
bool getVoxOn();
|
||||||
|
|
||||||
|
// Vox Threshold
|
||||||
|
void setVoxOpenThresh(uint16_t vox_open_thresh); // When vssi > th_h_vox, then vox will be 1(unit mV )
|
||||||
|
uint16_t getVoxOpenThresh();
|
||||||
|
void setVoxShutThresh(uint16_t vox_shut_thresh); // When vssi < th_l_vox && time delay meet, then vox will be 0 (unit mV )
|
||||||
|
uint16_t getVoxShutThresh();
|
||||||
|
|
||||||
|
// Tail Noise
|
||||||
|
void enableTailNoiseElim();
|
||||||
|
void disableTailNoiseElim();
|
||||||
|
bool getTailNoiseElimEnabled();
|
||||||
|
|
||||||
|
// tail noise shift select
|
||||||
|
// Select ctcss phase shift when use tail eliminating function when TX
|
||||||
|
// 00 = 120 degree shift
|
||||||
|
// 01 = 180 degree shift
|
||||||
|
// 10 = 240 degree shift
|
||||||
|
// 11 = reserved
|
||||||
|
void setShiftSelect(uint16_t shift_sel);
|
||||||
|
uint16_t getShiftSelect();
|
||||||
|
|
||||||
|
// DTMF
|
||||||
|
void setDTMFC0(uint16_t freq);
|
||||||
|
uint16_t getDTMFC0();
|
||||||
|
void setDTMFC1(uint16_t freq);
|
||||||
|
uint16_t getDTMFC1();
|
||||||
|
void setDTMFC2(uint16_t freq);
|
||||||
|
uint16_t getDTMFC2();
|
||||||
|
void setDTMFC3(uint16_t freq);
|
||||||
|
uint16_t getDTMFC3();
|
||||||
|
void setDTMFC4(uint16_t freq);
|
||||||
|
uint16_t getDTMFC4();
|
||||||
|
void setDTMFC5(uint16_t freq);
|
||||||
|
uint16_t getDTMFC5();
|
||||||
|
void setDTMFC6(uint16_t freq);
|
||||||
|
uint16_t getDTMFC6();
|
||||||
|
void setDTMFC7(uint16_t freq);
|
||||||
|
uint16_t getDTMFC7();
|
||||||
|
|
||||||
|
// TX FM deviation
|
||||||
|
void setFMVoiceCssDeviation(uint16_t deviation);
|
||||||
|
uint16_t getFMVoiceCssDeviation();
|
||||||
|
void setFMCssDeviation(uint16_t deviation);
|
||||||
|
uint16_t getFMCssDeviation();
|
||||||
|
|
||||||
|
// RX voice range
|
||||||
|
void setVolume1(uint16_t volume);
|
||||||
|
uint16_t getVolume1();
|
||||||
|
void setVolume2(uint16_t volume);
|
||||||
|
uint16_t getVolume2();
|
||||||
|
|
||||||
|
// GPIO
|
||||||
|
void setGpioMode(uint16_t gpio, uint16_t mode);
|
||||||
|
void setGpioHiZ(uint16_t gpio);
|
||||||
|
void setGpioFcn(uint16_t gpio);
|
||||||
|
void setGpioLow(uint16_t gpio);
|
||||||
|
void setGpioHi(uint16_t gpio);
|
||||||
|
uint16_t getGpioMode(uint16_t gpio);
|
||||||
|
|
||||||
|
// Int
|
||||||
|
void enableInterrupt(uint16_t interrupt);
|
||||||
|
void disableInterrupt(uint16_t interrupt);
|
||||||
|
bool getInterruptEnabled(uint16_t interrupt);
|
||||||
|
|
||||||
|
// ST mode
|
||||||
|
void setStMode(uint16_t mode);
|
||||||
|
uint16_t getStMode();
|
||||||
|
void setStFullAuto();
|
||||||
|
void setStRxAutoTxManu();
|
||||||
|
void setStFullManu();
|
||||||
|
|
||||||
|
// Pre-emphasis, De-emphasis filter
|
||||||
|
void bypassPreDeEmph();
|
||||||
|
void usePreDeEmph();
|
||||||
|
bool getPreDeEmphEnabled();
|
||||||
|
|
||||||
|
// Read Only Status Registers
|
||||||
|
int16_t readRSSI();
|
||||||
|
uint16_t readVSSI();
|
||||||
|
uint16_t readDTMFIndex(); // may want to split this into two (index1 and index2)
|
||||||
|
uint16_t readDTMFCode();
|
||||||
|
|
||||||
|
// set output power of radio
|
||||||
|
void setRfPower(uint8_t pwr);
|
||||||
|
|
||||||
|
// channel helper functions
|
||||||
|
bool setGMRSChannel(uint8_t channel);
|
||||||
|
bool setFRSChannel(uint8_t channel);
|
||||||
|
bool setMURSChannel(uint8_t channel);
|
||||||
|
bool setWXChannel(uint8_t channel);
|
||||||
|
uint8_t scanWXChannel();
|
||||||
|
|
||||||
|
|
||||||
|
// restrictions control
|
||||||
|
void dangerMode();
|
||||||
|
void safeMode();
|
||||||
|
|
||||||
|
// utilities
|
||||||
|
uint32_t scanMode(uint32_t start,uint32_t stop, uint8_t speed, 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 findWhitespaceChannels(uint32_t buffer[],uint8_t buffsize, uint8_t dwell, uint16_t threshold);
|
||||||
|
void buttonMode(uint8_t mode);
|
||||||
|
void isr_ptt();
|
||||||
|
void isr_reset();
|
||||||
|
void morseOut(char buffer[HAMSHIELD_MORSE_BUFFER_SIZE]);
|
||||||
|
char morseLookup(char letter);
|
||||||
|
bool waitForChannel(long timeout, long breakwindow);
|
||||||
|
void SSTVVISCode(int code);
|
||||||
|
void SSTVTestPattern(int code);
|
||||||
|
void toneWait(uint16_t freq, long timer);
|
||||||
|
void toneWaitU(uint16_t freq, long timer);
|
||||||
|
bool parityCalc(int code);
|
||||||
|
// void AFSKOut(char buffer[80]);
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
uint8_t devAddr;
|
||||||
|
uint16_t radio_i2c_buf[4];
|
||||||
|
int pwr_control_pin;
|
||||||
|
uint32_t radio_frequency;
|
||||||
|
uint32_t FRS[];
|
||||||
|
uint32_t GMRS[];
|
||||||
|
uint32_t MURS[];
|
||||||
|
uint32_t WX[];
|
||||||
|
|
||||||
|
|
||||||
|
// int8_t A1846S::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout);
|
||||||
|
// int8_t A1846S::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout);
|
||||||
|
// int8_t A1846S::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout);
|
||||||
|
// int8_t A1846S::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout);
|
||||||
|
// bool A1846S::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
|
||||||
|
// bool A1846S::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* _HAMSHIELD_H_ */
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,269 @@
|
||||||
|
// I2Cdev library collection - Main I2C device class header file
|
||||||
|
// Abstracts bit and byte I2C R/W functions into a convenient class
|
||||||
|
// 6/9/2012 by Jeff Rowberg <jeff@rowberg.net>
|
||||||
|
//
|
||||||
|
// Changelog:
|
||||||
|
// 2013-05-06 - add Francesco Ferrara's Fastwire v0.24 implementation with small modifications
|
||||||
|
// 2013-05-05 - fix issue with writing bit values to words (Sasquatch/Farzanegan)
|
||||||
|
// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire
|
||||||
|
// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation
|
||||||
|
// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums)
|
||||||
|
// 2011-10-03 - added automatic Arduino version detection for ease of use
|
||||||
|
// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications
|
||||||
|
// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x)
|
||||||
|
// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default
|
||||||
|
// 2011-08-02 - added support for 16-bit registers
|
||||||
|
// - fixed incorrect Doxygen comments on some methods
|
||||||
|
// - added timeout value for read operations (thanks mem @ Arduino forums)
|
||||||
|
// 2011-07-30 - changed read/write function structures to return success or byte counts
|
||||||
|
// - made all methods static for multi-device memory savings
|
||||||
|
// 2011-07-28 - initial release
|
||||||
|
|
||||||
|
/* ============================================
|
||||||
|
I2Cdev device library code is placed under the MIT license
|
||||||
|
Copyright (c) 2013 Jeff Rowberg
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in
|
||||||
|
all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
THE SOFTWARE.
|
||||||
|
===============================================
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _I2CDEV_RDA_H_
|
||||||
|
#define _I2CDEV_RDA_H_
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
// I2C interface implementation setting
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE
|
||||||
|
//#define I2CDEV_IMPLEMENTATION I2CDEV_BUILTIN_FASTWIRE
|
||||||
|
|
||||||
|
// comment this out if you are using a non-optimal IDE/implementation setting
|
||||||
|
// but want the compiler to shut up about it
|
||||||
|
#define I2CDEV_IMPLEMENTATION_WARNINGS
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
// I2C interface implementation options
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
#define I2CDEV_ARDUINO_WIRE 1 // Wire object from Arduino
|
||||||
|
#define I2CDEV_BUILTIN_NBWIRE 2 // Tweaked Wire object from Gene Knight's NBWire project
|
||||||
|
// ^^^ NBWire implementation is still buggy w/some interrupts!
|
||||||
|
#define I2CDEV_BUILTIN_FASTWIRE 3 // FastWire object from Francesco Ferrara's project
|
||||||
|
#define I2CDEV_I2CMASTER_LIBRARY 4 // I2C object from DSSCircuits I2C-Master Library at https://github.com/DSSCircuits/I2C-Master-Library
|
||||||
|
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
// Arduino-style "Serial.print" debug constant (uncomment to enable)
|
||||||
|
// -----------------------------------------------------------------------------
|
||||||
|
//#define I2CDEV_SERIAL_DEBUG
|
||||||
|
|
||||||
|
#ifdef ARDUINO
|
||||||
|
#if ARDUINO < 100
|
||||||
|
#include "WProgram.h"
|
||||||
|
#else
|
||||||
|
#include "Arduino.h"
|
||||||
|
#endif
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
|
||||||
|
#include <Wire.h>
|
||||||
|
#endif
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_I2CMASTER_LIBRARY
|
||||||
|
#include <I2C.h>
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// 1000ms default read timeout (modify with "I2Cdev::readTimeout = [ms];")
|
||||||
|
#define I2CDEV_DEFAULT_READ_TIMEOUT 1000
|
||||||
|
|
||||||
|
class I2Cdev {
|
||||||
|
public:
|
||||||
|
I2Cdev();
|
||||||
|
|
||||||
|
static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout);
|
||||||
|
|
||||||
|
static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
|
||||||
|
static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
|
||||||
|
static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
|
||||||
|
static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
|
||||||
|
static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
|
||||||
|
static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
|
||||||
|
static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
|
||||||
|
static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data);
|
||||||
|
|
||||||
|
static uint16_t readTimeout;
|
||||||
|
};
|
||||||
|
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
|
||||||
|
//////////////////////
|
||||||
|
// FastWire 0.24
|
||||||
|
// This is a library to help faster programs to read I2C devices.
|
||||||
|
// Copyright(C) 2012
|
||||||
|
// Francesco Ferrara
|
||||||
|
//////////////////////
|
||||||
|
|
||||||
|
/* Master */
|
||||||
|
#define TW_START 0x08
|
||||||
|
#define TW_REP_START 0x10
|
||||||
|
|
||||||
|
/* Master Transmitter */
|
||||||
|
#define TW_MT_SLA_ACK 0x18
|
||||||
|
#define TW_MT_SLA_NACK 0x20
|
||||||
|
#define TW_MT_DATA_ACK 0x28
|
||||||
|
#define TW_MT_DATA_NACK 0x30
|
||||||
|
#define TW_MT_ARB_LOST 0x38
|
||||||
|
|
||||||
|
/* Master Receiver */
|
||||||
|
#define TW_MR_ARB_LOST 0x38
|
||||||
|
#define TW_MR_SLA_ACK 0x40
|
||||||
|
#define TW_MR_SLA_NACK 0x48
|
||||||
|
#define TW_MR_DATA_ACK 0x50
|
||||||
|
#define TW_MR_DATA_NACK 0x58
|
||||||
|
|
||||||
|
#define TW_OK 0
|
||||||
|
#define TW_ERROR 1
|
||||||
|
|
||||||
|
class Fastwire {
|
||||||
|
private:
|
||||||
|
static boolean waitInt();
|
||||||
|
|
||||||
|
public:
|
||||||
|
static void setup(int khz, boolean pullup);
|
||||||
|
static byte beginTransmission(byte device);
|
||||||
|
static byte write(byte value);
|
||||||
|
static byte writeBuf(byte device, byte address, byte *data, byte num);
|
||||||
|
static byte readBuf(byte device, byte address, byte *data, byte num);
|
||||||
|
static void reset();
|
||||||
|
static byte stop();
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
|
||||||
|
// NBWire implementation based heavily on code by Gene Knight <Gene@Telobot.com>
|
||||||
|
// Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html
|
||||||
|
// Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html
|
||||||
|
|
||||||
|
#define NBWIRE_BUFFER_LENGTH 32
|
||||||
|
|
||||||
|
class TwoWire {
|
||||||
|
private:
|
||||||
|
static uint8_t rxBuffer[];
|
||||||
|
static uint8_t rxBufferIndex;
|
||||||
|
static uint8_t rxBufferLength;
|
||||||
|
|
||||||
|
static uint8_t txAddress;
|
||||||
|
static uint8_t txBuffer[];
|
||||||
|
static uint8_t txBufferIndex;
|
||||||
|
static uint8_t txBufferLength;
|
||||||
|
|
||||||
|
// static uint8_t transmitting;
|
||||||
|
static void (*user_onRequest)(void);
|
||||||
|
static void (*user_onReceive)(int);
|
||||||
|
static void onRequestService(void);
|
||||||
|
static void onReceiveService(uint8_t*, int);
|
||||||
|
|
||||||
|
public:
|
||||||
|
TwoWire();
|
||||||
|
void begin();
|
||||||
|
void begin(uint8_t);
|
||||||
|
void begin(int);
|
||||||
|
void beginTransmission(uint8_t);
|
||||||
|
//void beginTransmission(int);
|
||||||
|
uint8_t endTransmission(uint16_t timeout=0);
|
||||||
|
void nbendTransmission(void (*function)(int)) ;
|
||||||
|
uint8_t requestFrom(uint8_t, int, uint16_t timeout=0);
|
||||||
|
//uint8_t requestFrom(int, int);
|
||||||
|
void nbrequestFrom(uint8_t, int, void (*function)(int));
|
||||||
|
void send(uint8_t);
|
||||||
|
void send(uint8_t*, uint8_t);
|
||||||
|
//void send(int);
|
||||||
|
void send(char*);
|
||||||
|
uint8_t available(void);
|
||||||
|
uint8_t receive(void);
|
||||||
|
void onReceive(void (*)(int));
|
||||||
|
void onRequest(void (*)(void));
|
||||||
|
};
|
||||||
|
|
||||||
|
#define TWI_READY 0
|
||||||
|
#define TWI_MRX 1
|
||||||
|
#define TWI_MTX 2
|
||||||
|
#define TWI_SRX 3
|
||||||
|
#define TWI_STX 4
|
||||||
|
|
||||||
|
#define TW_WRITE 0
|
||||||
|
#define TW_READ 1
|
||||||
|
|
||||||
|
#define TW_MT_SLA_NACK 0x20
|
||||||
|
#define TW_MT_DATA_NACK 0x30
|
||||||
|
|
||||||
|
#define CPU_FREQ 16000000L
|
||||||
|
#define TWI_FREQ 100000L
|
||||||
|
#define TWI_BUFFER_LENGTH 32
|
||||||
|
|
||||||
|
/* TWI Status is in TWSR, in the top 5 bits: TWS7 - TWS3 */
|
||||||
|
|
||||||
|
#define TW_STATUS_MASK (_BV(TWS7)|_BV(TWS6)|_BV(TWS5)|_BV(TWS4)|_BV(TWS3))
|
||||||
|
#define TW_STATUS (TWSR & TW_STATUS_MASK)
|
||||||
|
#define TW_START 0x08
|
||||||
|
#define TW_REP_START 0x10
|
||||||
|
#define TW_MT_SLA_ACK 0x18
|
||||||
|
#define TW_MT_SLA_NACK 0x20
|
||||||
|
#define TW_MT_DATA_ACK 0x28
|
||||||
|
#define TW_MT_DATA_NACK 0x30
|
||||||
|
#define TW_MT_ARB_LOST 0x38
|
||||||
|
#define TW_MR_ARB_LOST 0x38
|
||||||
|
#define TW_MR_SLA_ACK 0x40
|
||||||
|
#define TW_MR_SLA_NACK 0x48
|
||||||
|
#define TW_MR_DATA_ACK 0x50
|
||||||
|
#define TW_MR_DATA_NACK 0x58
|
||||||
|
#define TW_ST_SLA_ACK 0xA8
|
||||||
|
#define TW_ST_ARB_LOST_SLA_ACK 0xB0
|
||||||
|
#define TW_ST_DATA_ACK 0xB8
|
||||||
|
#define TW_ST_DATA_NACK 0xC0
|
||||||
|
#define TW_ST_LAST_DATA 0xC8
|
||||||
|
#define TW_SR_SLA_ACK 0x60
|
||||||
|
#define TW_SR_ARB_LOST_SLA_ACK 0x68
|
||||||
|
#define TW_SR_GCALL_ACK 0x70
|
||||||
|
#define TW_SR_ARB_LOST_GCALL_ACK 0x78
|
||||||
|
#define TW_SR_DATA_ACK 0x80
|
||||||
|
#define TW_SR_DATA_NACK 0x88
|
||||||
|
#define TW_SR_GCALL_DATA_ACK 0x90
|
||||||
|
#define TW_SR_GCALL_DATA_NACK 0x98
|
||||||
|
#define TW_SR_STOP 0xA0
|
||||||
|
#define TW_NO_INFO 0xF8
|
||||||
|
#define TW_BUS_ERROR 0x00
|
||||||
|
|
||||||
|
//#define _MMIO_BYTE(mem_addr) (*(volatile uint8_t *)(mem_addr))
|
||||||
|
//#define _SFR_BYTE(sfr) _MMIO_BYTE(_SFR_ADDR(sfr))
|
||||||
|
|
||||||
|
#ifndef sbi // set bit
|
||||||
|
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||||
|
#endif // sbi
|
||||||
|
|
||||||
|
#ifndef cbi // clear bit
|
||||||
|
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||||
|
#endif // cbi
|
||||||
|
|
||||||
|
extern TwoWire Wire;
|
||||||
|
|
||||||
|
#endif // I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE
|
||||||
|
|
||||||
|
#endif /* _I2CDEV_RDA_H_ */
|
Loading…
Reference in New Issue