Add files via upload

master
roncarr880 2019-03-25 14:10:29 -04:00 zatwierdzone przez GitHub
rodzic aa338904b0
commit 70b235bbf1
Nie znaleziono w bazie danych klucza dla tego podpisu
ID klucza GPG: 4AEE18F83AFDEB23
1 zmienionych plików z 259 dodań i 293 usunięć

Wyświetl plik

@ -3,6 +3,8 @@
// Arduino, QRP Labs Arduino shield, SI5351 clock, QRP Labs RX module
// NOTE: The tx bias pot works in reverse, fully clockwise is off.
// !!! extend lower freq limit down to 60 khz for wwvb
#include <Wire.h>
#include <FreqCount.h> // one UNO I have does not work correctly with this library, another one does
@ -12,13 +14,14 @@
#define CLK0_EN 1
#define CLK1_EN 2
#define CLK2_EN 4
#define FREQ 7038600 // starting freq
#define DIV 14 // starting divider
#define RDIV 2 // starting sub divider ( 13 meg breakpoint for div = 1 )
#define FREQ 14095600 //7038600 // starting freq
#define DIV 14 // 14 // starting divider for 4*freq*RDIV
#define RDIV 1 //2 // starting sub divider ( 13 meg breakpoint for div = 1 )
#define CAT_MODE 0 // computer control of TX
#define FRAME_MODE 1 // or self timed frame (stand alone mode)
#define stage(c) Serial.write(c)
// use even dividers between 6 and 254 for lower jitter
// freq range 2 to 150 without using the post dividers
// we are using the post dividers
@ -29,14 +32,15 @@ uint32_t freq = FREQ; // ssb vfo freq
const uint32_t cal_freq = 3000000; // calibrate frequency
const uint32_t cal_divider = 200;
uint32_t divider = DIV; // 7 mhz with Rdiv of 8, 28 mhz with Rdiv of 2
uint32_t audio_freq = 1500; // wspr 1400 to 1600 offset from base vfo freq
uint32_t audio_freq = 1538; // wspr 1400 to 1600 offset from base vfo freq
uint8_t Rdiv = RDIV;
uint8_t operate_mode = FRAME_MODE; // start in stand alone timing mode
uint8_t wspr_tx_enable;
uint8_t wspr_tx_enable; // transmit enable
uint8_t wspr_tx_cancel; // CAT control RX command
uint8_t cal_enable;
long tm_correct_count = 10753;
int8_t tm_correction = 0;
long tm_correct_count = 10753; // add or sub one ms for time correction per this many ms
int8_t tm_correction = 0; // 0, 1 or -1 time correction
// Download WSPRcode.exe from http://physics.princeton.edu/pulsar/K1JT/WSPRcode.exe and run it in a dos window
// Type (for example): WSPRcode "K1ABC FN33 37" 37 is 5 watts, 30 is 1 watt, 33 is 2 watts, 27 is 1/2 watt
@ -68,8 +72,8 @@ struct BAND {
struct BAND band_info[6] = { // filter
{ 7, 40000, 600000 }, // 630m
{ A0, 600000, 2500000 }, // 160m
{ 10, 2500000, 6000000 }, // 60m
{ 11, 6000000, 11500000 }, // 30m
{ 10, 2500000, 5000000 }, // 80m
{ 11, 5000000, 11500000 }, // 30m
{ 12,11500000, 20000000 }, // 17m
{ A3,20000000, 30000000 } // 10m
};
@ -77,9 +81,9 @@ struct BAND band_info[6] = { // filter
void setup() {
int i;
uint8_t i;
Serial.begin(38400);
Serial.begin(1200); // TenTec Argo V baud rate
Wire.begin();
Wire.setClock(400000);
@ -127,7 +131,8 @@ uint8_t band_change(){
for( band = 0; band < 6; ++band ){
if( freq > band_info[band].low && freq <= band_info[band].high ) break;
}
if( band < 6 ) digitalWrite( band_info[band].pin,LOW);
if( band == 6 ) band = 5; // default band
digitalWrite( band_info[band].pin,LOW);
return 1;
}
@ -176,7 +181,7 @@ static unsigned long ms;
ms = millis();
frame_timer(ms);
if( wspr_tx_enable ) wspr_tx(ms);
if( wspr_tx_enable || wspr_tx_cancel ) wspr_tx(ms);
if( cal_enable ) run_cal();
}
@ -245,6 +250,10 @@ static int i;
static unsigned long timer;
static uint8_t mod;
if( wspr_tx_cancel ){ // quit early or just the end of the message
if( i < 160 ) i = 162; // let finish if near the end, else force done
}
if( i != 0 && (t - timer) < 683 ) return; // baud time is 682.66666666 ms
timer = t;
++mod; mod &= 3;
@ -253,7 +262,7 @@ static uint8_t mod;
if( i == 162 ){
tx_off();
i = 0; // setup for next time to begin at zero index
wspr_tx_enable = 0; // flag done
wspr_tx_cancel = wspr_tx_enable = 0; // flag done
return;
}
// set the frequency
@ -343,322 +352,279 @@ uint8_t R;
}
/****** Elecraft Command Emulation ******/
// K3 emulation code
// !!!!!!comment out errors for now - clean up when working
void get_freq(uint32_t vfo ){ /* report vfo */
/*****************************************************************************************/
// TenTec Argonaut V CAT emulation
//if( mode == CW && fun_selected[0] != WIDE ) vfo = vfo + (( sideband == USB ) ? mode_offset : - mode_offset);
stage_str("000");
if( vfo < 10000000 ) stage('0');
stage_long(vfo);
}
//int un_stage(){ /* send a char on serial */
//char c;
// if( stg_in == stg_out ) return 0;
// c = stg_buf[stg_out++];
// stg_out &= ( STQUESIZE - 1);
// Serial.write(c);
// return 1;
//}
#define CMDLEN 20
char command[CMDLEN];
uint8_t vfo = 'A';
void radio_control() {
static int expect_len = 0;
static int len = 0;
static char cmd;
static String command = "";
String lcommand;
char c;
int ritl; // local copy of rit
int sm;
// int bat; /* put battery voltage in front panel revision */
int done;
if (Serial.available() == 0) return;
done = 0;
while( Serial.available() ){
c = Serial.read();
if( c < ' ' ) continue;
command += c;
if( c == ';' ) break;
}
// !!! test for setup command here
if( c != ';' ) return; /* command not complete yet */
operate_mode = CAT_MODE; // switch to CAT MODE when receive a ';'
lcommand = command.substring(0,2);
// special commands that look like query commands
if( lcommand == "TX" ){
wspr_tx_enable = 1; // could use this to set the frame clock at 0 or 1 sec.
return;
}
if( lcommand == "RX" ) return; // let wspr tx finish normally
// Otherwise will need to make the wspr index a global to shortcut tx.
if( command.substring(2,3) == ";" || command.substring(2,4) == "$;" || command.substring(0,2) == "RV" ){ /* it is a get command */
stage_str(lcommand); /* echo the command */
if( command.substring(2,3) == "$") stage('$');
if (lcommand == "IF") {
/*
RSP format: IF[f]*****+yyyyrx*00tmvspbd1*; where the fields are defined as follows:
[f] Operating frequency, excluding any RIT/XIT offset (11 digits; see FA command format)
* represents a space (BLANK, or ASCII 0x20)
+ either "+" or "-" (sign of RIT/XIT offset)
yyyy RIT/XIT offset in Hz (range is -9999 to +9999 Hz when computer-controlled)
r 1 if RIT is on, 0 if off
x 1 if XIT is on, 0 if off
t 1 if the K3 is in transmit mode, 0 if receive
m operating mode (see MD command)
v receive-mode VFO selection, 0 for VFO A, 1 for VFO B
s 1 if scan is in progress, 0 otherwise
p 1 if the transceiver is in split mode, 0 otherwise
b Basic RSP format: always 0; K2 Extended RSP format (K22): 1 if present IF response
is due to a band change; 0 otherwise
d Basic RSP format: always 0; K3 Extended RSP format (K31): DATA sub-mode,
if applicable (0=DATA A, 1=AFSK A, 2= FSK D, 3=PSK D)
*/
get_freq(freq );
stage_str(" ");
ritl= 0; // rit;
if( ritl >= 0 ) stage_str("+0");
else{
stage_str("-0");
ritl = - ritl;
}
if( ritl < 100 ) stage('0');
if( ritl < 10 ) stage('0'); //IF[f]*****+yyyyrx*00tmvspbd1*;
stage_num(ritl);
stage_str("10 0003"); /* rit,xit,xmit,cw mode */
// if( split == 2 ) stage_str("10");
/* else */ stage_str("00");
// if( split ) stage('1');
/* else */ stage('0');
stage_str("001 ");
}
else if(lcommand == "FA") get_freq( freq );
else if(lcommand == "FB") get_freq( freq );
else if(lcommand == "RT") stage('0') ; //{ if(rit_state) stage('1'); else stage('0'); }
else if(lcommand == "FR") stage('0');
else if(lcommand == "FT"){
// if( split ) stage('1');
/* else */ stage('0');
}
else if( lcommand == "KS"){
stage('0');
stage_num(12); //(wpm);
}
else if(lcommand == "XF") stage_num(2); // bandwidth fun_selected[0]);
else if(lcommand == "AG") stage_str("030");
else if(lcommand == "RG") stage_str("250");
else if(lcommand == "PC") stage_str("005");
else if(lcommand == "FW") {stage_str("0000") ; stage_num(2);} //stage_num(fun_selected[0]);
else if(lcommand == "IS") stage_str("0000");
else if(lcommand == "AN") stage('1');
else if(lcommand == "GT") stage_str("004");
else if(lcommand == "TQ") stage_num(0); //stage_num(transmitting);
else if(lcommand == "PA" || lcommand == "XT" || lcommand == "NB" ) stage('0');
else if(lcommand == "RA") stage_str("00");
else if(lcommand == "OM") stage_str("-----F------");
else if(lcommand == "LK") stage_num( 0 ); //stage_num(user[LOCK]);
else if(lcommand == "MD") stage_num(2); // (3-mode ); // stage('3');
else if(lcommand == "RV" && command.substring(2,3) == "F"){ /* battery voltage in the revision field */
stage(command.charAt(2));
// bat = battery(0);
// stage_num(bat/10);
// stage('.');
// stage_num(bat % 10);
stage('0');
}
else if(lcommand == "RV" && command.substring(2,3) == "A"){ /* swap status in revision field */
stage(command.charAt(2));
// if( split == 2 ) stage_str("SWAP ");
/*else*/ stage_str(" ");
}
else if(lcommand == "RV"){ // revisions
stage(command.charAt(2));
stage_str(" ");
}
else if(lcommand == "SM"){
stage_str("00");
sm = 9; //smeter(0);
if( sm < 10 ) stage('0');
stage_num(sm);
}
else if(lcommand == "ID"){
stage_str("017");
}
else if(lcommand == "BW"){
stage_str("0300");
}
else{
stage('0'); /* don't know what it is */
}
stage(';'); /* response terminator */
command[len] = c;
if(++len >= CMDLEN ) len= 0; /* something wrong */
if( len == 1 ) cmd = c; /* first char */
/* sync ok ? */
if( cmd == '?' || cmd == '*' || cmd == '#' ); /* ok */
else{
len= 0;
return;
}
if( len == 2 && cmd == '*' ) expect_len = lookup_len(c); /* for binary data on the link */
if( (expect_len == 0 && c == '\r') || (len == expect_len) ){
done = 1;
break;
}
}
else set_k3(lcommand,command); /* else it is a set command ? */
if( done == 0 ) return; /* command not complete yet */
if( cmd == '?' ) get_cmd(), operate_mode = CAT_MODE; // switch modes on query cat command
if( cmd == '*' ) set_cmd();
if( cmd == '#' ) pnd_cmd();
/* prepare for next command */
len = expect_len= 0;
// if( cmd != '?' ){ // does wsjt need to see the G returned for query commands?. Yes it does.
stage('G'); /* they are all good commands */
stage('\r');
// }
}
int lookup_len(char cmd2){ /* just need the length of the command */
int len;
command = ""; /* clear for next command */
switch(cmd2){ /* get length of argument */
case 'X': len = 0; break;
case 'A':
case 'B': len = 4; break;
case 'E':
case 'P':
case 'M': len = 2; break;
default: len = 1; break ;
}
return len+3; /* add in *A and cr on the end */
}
void set_cmd(){
char cmd2;
long arg;
char val1;
int val2;
unsigned long val4;
void set_k3(String lcom, String com ){
String arg;
uint32_t val;
char buf[25];
cmd2 = command[1];
switch(cmd2){
case 'X': stage_str("RADIO START"); stage('\r'); break;
case 'O': /* split */
val1 = command[2];
// if( val1 && user[SPLIT] ) val1 = 0; /* toggle from HRD instead of zero to shut off? */
// if( val1 ) split= user[SPLIT] = 1;
// else{
// if( split == 2 ) rx_vfo = tx_vfo;
// else tx_vfo = rx_vfo;
// split= user[SPLIT] = user[SWAPVFO] = 0;
// }
break;
case 'A':
case 'B':
val4 = get_long();
// if( mode == CW && fun_selected[0] != WIDE ) val4 = val4 - (( sideband == USB ) ? mode_offset : - mode_offset);
// cat_band_change(val4); // check for band change
// if( cmd2 == 'B' ) tx_vfo = val4;
// else{
// rx_vfo = val4;
// if( split == 0 ) tx_vfo = val4;
// }
qsy(val4);
break;
case 'E':
if( command[2] == 'V' ) vfo = command[3];
break;
case 'W': /* bandwidth */
val1 = command[2];
// if( val1 < 12 ) fun_selected[0] = NARROW; /* narrow */
// else if( val1 > 23 ) fun_selected[0] = WIDE; /* wide */
// else fun_selected[0] = MEDIUM;
// set_band_width(fun_selected[0]);
break;
case 'K': /* putting keying speed on the Noise Blanker slider. Range is 10 to 19 */
/* or could be easily doubled for a range of 10 to 28 - if so change the get cmd also*/
// wpm = command[2] + 10;
break;
case 'T': /* added tuning rate as a command */
// set_tuning_rate(command[2]);
// fun_selected[1] = command[2];
break;
} /* end switch */
if( lcom == "FA" || lcom == "FB" ){ /* set vfo freq */
arg = com.substring(2,13);
arg.toCharArray(buf,25);
val = atol(buf);
// if( mode == CW && fun_selected[0] != WIDE ) val = val - (( sideband == USB ) ? mode_offset : - mode_offset);
// cat_band_change((unsigned long)val);
// if( lcom == "FB" && xit_state ) xit = freq - val;
if( lcom == "FA" ) qsy(val);
// freq_display(freq);
}
else if( lcom == "KS" ){ /* keyer speed */
arg= com.substring(2,5);
arg.toCharArray(buf,25);
val = atol(buf);
// wpm = val;
}
else if( lcom == "LK" ){ /* lock vfo's */
// val = com.charAt(2);
// if( val == '$' ) val = com.charAt(3);
// user[LOCK] = val - '0';
}
else if( lcom == "FW" ){ /* xtal filter select */
val = com.charAt(6) - '0';
if( val < 4 && val != 0 ){
// fun_selected[0] = val;
// set_band_width(val);
}
}
else if( lcom == "FT" ){ /* enter split */
val = com.charAt(2) - '0';
if( val == 0 ){
// if( split == 2 ) rx_vfo = tx_vfo;
// else tx_vfo = rx_vfo;
}
// split = user[SPLIT] = val;
// user[SWAPVFO] = 0;
}
else if( lcom == "FR" ){ /* cancel split ? */
val = com.charAt(2);
if( val == '0' ){
// if( split == 2 ) rx_vfo = tx_vfo;
// else tx_vfo = rx_vfo;
// split = user[SPLIT] = user[SWAPVFO] = 0;
}
}
else if( com == "SWT11;" ){ /* A/B tap. swap (listen) vfo */
// if( split < 2 ){ /* turns on split if off */
// split = 2;
// user[SPLIT]= user[SWAPVFO] = 1;
// }
// else{ /* back to listen on RX freq, stay in split */
// split = 1;
// user[SWAPVFO] = 0;
// }
// update_frequency(DISPLAY_UPDATE); /* listen on selected vfo */
}
//update_frequency(DISPLAY_UPDATE);
//write_sleds(sleds[fun_selected[function]]);
//write_fleds(fleds[function], 1); /* update on/off status on FGRN led */
//led_on_timer = 1000;
}
void get_cmd(){
char cmd2;
long arg;
int bat;
int len;
/******************* stage buffer to avoid serial.print blocking ****************/
// modified to use serial function availableForWrite removing the need for a local
// character buffer
void stage( unsigned char c ){
Serial.write(c);
// stg_buf[stg_in++] = c;
// stg_in &= ( STQUESIZE - 1 );
cmd2 = command[1];
// nope breaks HRD also stage(command[0]); // does wsjt need to see the question mark ?
stage(cmd2);
switch(cmd2){
case 'A': //arg= rx_vfo;
case 'B':
arg = freq;
// if( cmd2 == 'B' ) arg= tx_vfo;
// if( mode == CW && fun_selected[0] != WIDE ) arg = arg + (( sideband == USB ) ? mode_offset : - mode_offset);
stage_long(arg);
break;
case 'V': /* version */
// stage(' ');
// bat = 135; // battery(0);
// stage_num(bat/10);
// stage('.');
// stage_num(bat % 10);
// if( user[SWAPVFO] ) stage_str(" SWAP");
stage_str("ER 1010-516");
break;
case 'W': /* receive bandwidth */
stage(30); //stage(40 - fun_selected[0] * 10 );
break;
case 'M': /* mode */
stage('1'); stage('1');
break;
case 'O': /* split */
//if( split ) stage(1);
//else stage(0);
stage(0);
break;
case 'P': /* passband slider */
stage_int( 3000 );
break;
case 'T': /* added tuning rate command */
//stage( fun_selected[1] );
break;
case 'E': /* vfo mode */
stage('V');
// if( split == 2 ) stage('B');
// else
stage(vfo);
break;
case 'S': /* signal strength */
stage(7);
stage(0);
break;
case 'C':
stage(0);
stage(wspr_tx_enable);
break;
case 'K': /* wpm on noise blanker slider */
stage( 15 - 10 );
break;
default: /* send zeros for unimplemented commands */
len= lookup_len(cmd2) - 3;
while( len-- ) stage(0);
break;
}
stage('\r');
// stage('\n'); // does wsjt need to see line feeds ?
}
void stage_str( String st ){
//int i;
//char c;
int i;
char c;
Serial.print(st);
// for( i = 0; i < st.length(); ++i ){
// c= st.charAt( i );
// stage(c);
// }
}
void stage_num( int val ){ /* send number in ascii */
//char buf[35];
//char c;
//int i;
Serial.print(val);
// itoa( val, buf, 10 );
// i= 0;
// while( c = buf[i++] ) stage(c);
for( i = 0; i < st.length(); ++i ){
c= st.charAt( i );
stage(c);
}
}
void stage_long( long val ){
//char buf[35];
//char c;
//int i;
Serial.print(val);
// ltoa( val, buf, 10 );
// i= 0;
// while( c = buf[i++] ) stage(c);
unsigned char c;
c= val >> 24;
stage(c);
c= val >> 16;
stage(c);
c= val >> 8;
stage(c);
c= val;
stage(c);
}
unsigned long get_long(){
union{
unsigned long v;
unsigned char ch[4];
}val;
int i;
/* end of K3 emulation functions */
#ifdef NOWAY
for( i = 0; i < 4; ++i) val.ch[i] = command[5-i]; // or i+2 for other endian
void tune_band_change( ){ // if tune past band region, switch to another filter and band registers
int b; // not saving the band info, so if band switch will go back to last save and not the band edge
b = check_band(freq);
if( b != band ){ // band change
band = b;
band_change2();
}
return val.v;
}
void cat_band_change( uint32_t val ){ /* detect if we have a large qsy */
int b;
b = check_band(val);
if( b != band ){ // band change
band = b;
freq = val;
rit = band_info[band].rit;
xit = band_info[band].xit;
rit_state = band_info[band].rit_state;
xit_state = band_info[band].xit_state;
// stp = band_info[band].stp;
mode = band_info[band].mode;
// tone_offset = band_info[band].tone_offset;
band_change2();
}
void stage_int( int val ){
unsigned char c;
c= val >> 8;
stage(c);
c= val;
stage(c);
}
int check_band( uint32_t val ){
int b;
b= 0;
val /= 100;
if( val < 5000000 ) b = 0;
if( val >= 5000000 && val < 6000000) b= 1;
if( val >= 6000000 && val < 8000000) b= 2;
if( val >= 8000000 && val < 12000000 ) b= 3;
if( val >= 12000000 && val < 16000000 ) b= 4;
if( val >= 16000000 ) b= 5;
return b;
}
int un_stage(){ /* send a char on serial */
void stage_num( int val ){ /* send number in ascii */
char buf[35];
char c;
int i;
if( stg_in == stg_out ) return 0;
c = stg_buf[stg_out++];
stg_out &= ( STQUESIZE - 1);
Serial.write(c);
return 1;
itoa( val, buf, 10 );
i= 0;
while( c = buf[i++] ) stage(c);
}
#endif
void pnd_cmd(){
char cmd2;
cmd2 = command[1];
switch(cmd2){
case 0: wspr_tx_cancel = 1; break;
case 1: wspr_tx_enable = 1; break;
}
}