Commit 53b8ba0e authored by Ondřej Kučera's avatar Ondřej Kučera
Browse files

add tx test (skips gps setup)

parent 6f182cf1
This diff is collapsed.
// Si5351_WSPR
//
// V1 code for WSPR pico ballon
// code by OK1CDJ
// First message is standard WSPR message type1
// OK1CDJ JO70 10
// Second message is for telemetry
// 0C1XXX XX00 00
// ||| | |_____ altitude in 100m resolution to 9900 m - 01 - 100m,, 10 - 1000m, 99 - 9900m
// || |
// || |_battery voltage from A0 encoded - A=1 B=2, C=3 ... AA - 0V, BA - 1V
// ||____AA-XX small field from locator
// |____ temperature roudned to 2 deg encoded to A-Z, A=10, Z=-40 deg C
//
// Time code adapted from the TimeSerial.ino example from the Time library.
// Hardware Requirements
// ---------------------
// This firmware must be run on an Arduino AVR microcontroller
//
// Required Libraries
// ------------------
// Etherkit Si5351 (Library Manager)
// Etherkit JTEncode (Library Manager)
// Time (Library Manager)
// Wire (Arduino Standard Library)
//
// TODO
// measure CORRECTION for better oscillator
// Band hopping
// encode temperature to A-Z
// Ublox init and reset
// safe routines to do reset (but we have no time in my loop, precise sync is required for WSPR transmttion)
#include <si5351.h>
#include <JTEncode.h>
#include <int.h>
#include <TimeLib.h>
#include "TinyGPS.h"
#include "Wire.h"
#define TONE_SPACING 146 // ~1.46 Hz
#define WSPR_CTC 10672 // CTC value for WSPR
#define SYMBOL_COUNT WSPR_SYMBOL_COUNT
#define CORRECTION 0
//#define CORRECTION 30000
//#define CORRECTION 360000 // 7 MHz
//#define CORRECTION 160000 // 7 MHz
#define TIME_HEADER "T" // Header tag for serial time sync message
#define TIME_REQUEST 7 // ASCII bell character requests a time sync message
#define TX_LED_PIN 12
#define SYNC_LED_PIN 13
// Global variables
Si5351 si5351;
JTEncode jtencode;
char *str;
//unsigned long freq = 10140200UL; // Change this
//unsigned long freq = 7040100UL; // Change this
unsigned long freq = 14097100UL;
//int qrg_i=0;
//unsigned long qrg[] = {7040100UL, 10140200UL, 14097100UL};
char call[7] = "OK1RAJ"; // Change this
char loc[5] = "AA00"; // Change this
uint8_t dbm = 10;
uint8_t tx_buffer[SYMBOL_COUNT];
char call2[7] = "0C1XXX"; // Change this
char loc2[5] = "AA00"; // Change this
TinyGPS gps;
long lat = 0, lon = 0, alt = 0;
unsigned long age;
int Year;
byte Month, Day, Hour, Minute, Second;
int first = 1;
float voltage;
int temperature = 0;
struct t_mtab {
char c, pat;
} ;
struct t_mtab morsetab[] = {
{'.', 106},
{',', 115},
{'?', 76},
{'/', 41},
{'A', 6},
{'B', 17},
{'C', 21},
{'D', 9},
{'E', 2},
{'F', 20},
{'G', 11},
{'H', 16},
{'I', 4},
{'J', 30},
{'K', 13},
{'L', 18},
{'M', 7},
{'N', 5},
{'O', 15},
{'P', 22},
{'Q', 27},
{'R', 10},
{'S', 8},
{'T', 3},
{'U', 12},
{'V', 24},
{'W', 14},
{'X', 25},
{'Y', 29},
{'Z', 19},
{'1', 62},
{'2', 60},
{'3', 56},
{'4', 48},
{'5', 32},
{'6', 33},
{'7', 35},
{'8', 39},
{'9', 47},
{'0', 63}
} ;
#define N_MORSE (sizeof(morsetab)/sizeof(morsetab[0]))
int dotlen;
int dashlen;
int speed = 20;
// Global variables used in ISRs
volatile bool proceed = false;
// Timer interrupt vector. This toggles the variable we use to gate
// each column of output to ensure accurate timing. Called whenever
// Timer1 hits the count set below in setup().
ISR(TIMER1_COMPA_vect)
{
proceed = true;
}
// Loop through the string, transmitting one character at a time.
void encode()
{
uint8_t i;
if (first == 1) {
first = 0;
jtencode.wspr_encode(call, loc, dbm, tx_buffer);
}
else {
first = 1;
jtencode.wspr_encode(call2, loc2, dbm, tx_buffer);
}
// Reset the tone to 0 and turn on the output
si5351.set_clock_pwr(SI5351_CLK0, 1);
//digitalWrite(TX_LED_PIN, HIGH);
// Now do the rest of the message
for (i = 0; i < SYMBOL_COUNT; i++)
{
si5351.set_freq((freq * 100) + (tx_buffer[i] * TONE_SPACING), SI5351_CLK0);
proceed = false;
while (!proceed);
}
// Turn off the output
si5351.set_clock_pwr(SI5351_CLK0, 0);
// digitalWrite(TX_LED_PIN, LOW);
}
void software_Reset() // Restarts program from beginning but does not reset the peripherals and registers
{
asm volatile (" jmp 0");
}
void lat2loc() {
int v;
long lat_loc = 0, lon_loc = 0;
/*
Refer to:
http://en.wikipedia.org/wiki/Maidenhead_Locator_System
*/
lon_loc = (lon / 10) + 18000000; // Step 1
lat_loc = (lat / 10) + 9000000; // Adjust so Locn AA is at the pole
loc[0] = 'A' + (lon_loc / 2000000); // Field
loc[1] = 'A' + (lat_loc / 1000000);
loc[2] = '0' + ((lon_loc % 2000000) / 200000); // Square
loc[3] = '0' + ((lat_loc % 1000000) / 100000);
loc[4] = 0;
call2[4] = 'A' + ((lon_loc % 200000) / 8333); // Subsquare .08333 is 5/60
call2[5] = 'A' + ((lat_loc % 100000) / 4166); // .04166 is 2.5/60
loc2[2] = '0' + (((alt / 10000) / 10) % 10); // tens digit
loc2[3] = '0' + ((alt / 10000) % 10); // ones digit
// voltage
v = int (voltage);
loc2[0] = 'A' + ((v / 10) % 10)-1; // tens digit
loc2[1] = 'A' + (v % 10)-1; // ones digit
loc2[4] = 0;
// temparature
if(temperature>10) temperature=10;
if(temperature<-40) temperature=-40;
call2[3] = 90-((temperature+40)/2);
/*
Serial.println("lat2loc");
Serial.println(loc);
Serial.println(loc2);
*/
// Serial.println(loc2);
}
// Measeure temperature by internal sensor of ATMEGA328p
int getTemp()
{
unsigned int wADC;
// The internal temperature has to be used
// with the internal reference of 1.1V.
// Channel 8 can not be selected with
// the analogRead function yet.
// Set the internal reference and mux.
ADMUX = (_BV(REFS1) | _BV(REFS0) | _BV(MUX3));
ADCSRA |= _BV(ADEN); // enable the ADC
delay(1); // wait for voltages to become stable.
ADCSRA |= _BV(ADSC); // Start the ADC
// Detect end-of-conversion
while (bit_is_set(ADCSRA, ADSC));
// Reading register "ADCW" takes care of how to read ADCL and ADCH.
wADC = ADCW;
// The returned temperature is raw.
return (wADC);
}
void setup()
{
// Use the Arduino's on-board LED as a keying indicator.
pinMode(TX_LED_PIN, OUTPUT);
pinMode(SYNC_LED_PIN, OUTPUT);
analogReference(INTERNAL);
digitalWrite(TX_LED_PIN, LOW);
digitalWrite(SYNC_LED_PIN, LOW);
Serial.begin(9600);
//resetGPS();---------------------------------------------------------------------------------------
//setupGPS();---------------------------------------------------------------------------------------
// enable the DC/DC converter on the GPS module
// it's a one time command, so you can comment it out later
//enableGPSdcdc();----------------------------------------------------------------------------------
// Initialize the Si5351
// Change the 2nd parameter in init if using a ref osc other
// than 25 MHz - 0
si5351.init(SI5351_CRYSTAL_LOAD_8PF, 25000000, CORRECTION);
// Set CLK0 output
si5351.set_freq(freq * 100, SI5351_CLK0);
si5351.drive_strength(SI5351_CLK0, SI5351_DRIVE_8MA); // Set for max power
si5351.set_clock_pwr(SI5351_CLK0, 0); // Disable the clock initially
// Set up Timer1 for interrupts every symbol period.
noInterrupts(); // Turn off interrupts.
TCCR1A = 0; // Set entire TCCR1A register to 0; disconnects
// interrupt output pins, sets normal waveform
// mode. We're just using Timer1 as a counter.
TCNT1 = 0; // Initialize counter value to 0.
TCCR1B = (1 << CS12) | // Set CS12 and CS10 bit to set prescale
(1 << CS10) | // to /1024
(1 << WGM12); // turn on CTC
// which gives, 64 us ticks
TIMSK1 = (1 << OCIE1A); // Enable timer compare interrupt.
OCR1A = WSPR_CTC; // Set up interrupt trigger count;
interrupts(); // Re-enable interrupts.
// setTime(0, 0, 0, 1, 1, 2019);
speed = 20;
dotlen = (1200 / speed);
dashlen = (3 * (1200 / speed));
str = "OK1RAJ OK1RAJ"; // Change this
sendmsg(str);
delay(2000);
sendmsg(str);
}
void loop()
{
// read voltage from AD1
voltage=analogRead(A1);
voltage = ( voltage/ 1024) * 48.1;
temperature = (getTemp() - 324.31) / 1.22;
while (Serial.available())
{
//processSyncMessage();
//Serial.println(timeStatus());
//Serial.println(alt);
if (gps.encode(Serial.read())) { // process gps messages
// when TinyGPS reports new data...
gps.get_position(&lat, &lon, &age);
alt = gps.altitude();
//Serial.println(alt);
gps.crack_datetime(&Year, &Month, &Day, &Hour, &Minute, &Second, NULL, &age);
if (age < 500) {
// set the Time to the latest GPS reading
setTime(Hour, Minute, Second, Day, Month, Year);
lat2loc();
}
}
}
if (timeStatus() == timeSet)
{
digitalWrite(SYNC_LED_PIN, HIGH); // LED on if synced
}
else
{
digitalWrite(SYNC_LED_PIN, LOW); // LED off if needs refresh
//send('L');
}
// Trigger every 2th minute
// WSPR should start on the 1st second of the minute, but there's a slight delay
// in this code because it is limited to 1 second resolution.
///*
if (timeStatus() == timeSet && minute() % 2 == 0 && second() == 0)
{
encode();
// we have time here for something to do outside time sync
// band hopping will be here
delay(300);
if (Serial.available())
{
if (gps.encode(Serial.read())) { // process gps messages
// when TinyGPS reports new data...
gps.get_position(&lat, &lon, &age);
alt = gps.altitude();
//if (age < 2000 ) {
// set the Time to the latest GPS reading
//setTime(Hour, Minute, Second, Day, Month, Year);
lat2loc();
//}
}
}
/* if(first=0){
si5351.set_freq(qrg[qrg_i] * 100, SI5351_CLK0);
si5351.drive_strength(SI5351_CLK0, SI5351_DRIVE_8MA); // Set for max power
si5351.set_clock_pwr(SI5351_CLK0, 0); // Disable the clock initially
qrg_i++;
if (qrg_i<3) qrg_i=0;
}*/
}
// */
}
void sendUBX(uint8_t *MSG, uint8_t len) {
Serial.flush();
Serial.write(0xFF); //preco toto na zaciatku spravy ?
delay(100);
for(int i=0; i<len; i++) {
Serial.write(MSG[i]);
}
}
void resetGPS() {
/*
Forced (Watchdog)
Coldstart
*/
uint8_t set_reset[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0x87, 0x00, 0x00, 0x94, 0xF5};
sendUBX(set_reset, sizeof(set_reset)/sizeof(uint8_t));
}
void setupGPS() {
//setGPS_NMEAoff(); test only
/*setGPS_GLLoff();
wait(1000);
setGPS_GSVoff();
wait(1000);
setGPS_VTGoff();
wait(1000);
setGPS_GSAoff();
wait(1000);
*/
setGPS_rate();
delay(1000);
setGPS_DynamicModel6();
delay(1000);
setGps_MaxPerformanceMode();
delay(1000);
// morse("V");
//turn off GSV
}
void FixUBXChecksum(unsigned char *Message, int Length)
{
int i;
unsigned char CK_A, CK_B;
CK_A = 0;
CK_B = 0;
for (i=2; i<(Length-2); i++)
{
CK_A = CK_A + Message[i];
CK_B = CK_B + CK_A;
}
Message[Length-2] = CK_A;
Message[Length-1] = CK_B;
}
void setupGPSpower() {
//Set GPS ot Power Save Mode
uint8_t setPSM[] = { 0xB5, 0x62, 0x06, 0x11, 0x02, 0x00, 0x08, 0x01, 0x22, 0x92 }; // Setup for Power Save Mode (Default Cyclic 1s)
sendUBX(setPSM, sizeof(setPSM)/sizeof(uint8_t));
}
void enableGPSdcdc() {
//enable GPS DC/DC converter
uint8_t setDC[] = {0xB5, 0x62, 0x06, 0x41, 0x0C, 0x00, 0x00, 0x00, 0x03, 0x1F, 0xC5, 0x90, 0xE1, 0x9F, 0xFF, 0xFF, 0xFE, 0xFF, 0x45, 0x79}; //B5 62 06 41 0C 00 00 00 03 1F C5 90 E1 9F FF FF FE FF 45 79
sendUBX(setDC, sizeof(setDC)/sizeof(uint8_t));
}
void setGPS_GSVoff()
{
int gps_set_sucess=0;
uint8_t setGSVoff[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x38};
while(!gps_set_sucess)
{
sendUBX(setGSVoff, sizeof(setGSVoff)/sizeof(uint8_t));
gps_set_sucess=getUBX_ACK(setGSVoff);
}
// morse("OK");
}
void setGPS_GLLoff()
{
int gps_set_sucess=0;
uint8_t setGLLoff[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2A};
while(!gps_set_sucess)
{
sendUBX(setGLLoff, sizeof(setGLLoff)/sizeof(uint8_t));
gps_set_sucess=getUBX_ACK(setGLLoff);
}
}
void setGPS_VTGoff()
{
int gps_set_sucess=0;
uint8_t setVTGoff[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x46};
while(!gps_set_sucess)
{
sendUBX(setVTGoff, sizeof(setVTGoff)/sizeof(uint8_t));
gps_set_sucess=getUBX_ACK(setVTGoff);
}
}
void setGPS_GSAoff()
{
int gps_set_sucess=0;
uint8_t setGSAoff[] = {0xB5, 0x62, 0x06, 0x01, 0x08, 0x00, 0xF0, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x31};
while(!gps_set_sucess)
{
sendUBX(setGSAoff, sizeof(setGSAoff)/sizeof(uint8_t));
gps_set_sucess=getUBX_ACK(setGSAoff);
}
}
void setGPS_rate()
{
//
int gps_set_sucess=0;
uint8_t setrate[] = {0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xF4, 0x01, 0x01, 0x00, 0x01, 0x00, 0x0B, 0x77 };
//
/* uint8_t request[] = {0xB5, 0x62, // Header
0x06, 0x08, // Class, ID
0x06, 0x00, // Payload length
0x00, 0x00, 0x01, 0x00, 0x00, 0x00, // Payload
0x00, 0x00}; // Checksum
// Fill in rate
request[6] = (unsigned char)(MilliSeconds & 0xFF);
request[7] = (unsigned char)(MilliSeconds >> 8);
*/
while(!gps_set_sucess)
{
sendUBX(setrate, sizeof(setrate)/sizeof(uint8_t));
gps_set_sucess=getUBX_ACK(setrate);
}
// morse("OK");
}
void setGPS_DynamicModel6()
{
/*
CFG-NAV5
Header: 0xB5, 0x62,
ID: 0x06, 0x24,
Length 0x24, 0x00,
mask 0xFF, 0xFF,
dynModel: 0x06, (Airborne <1g)
fixMode: 0x03,
fixedAlt: 0x00, 0x00, 0x00, 0x00,
fixedAltVar: 0x10, 0x27, 0x00, 0x00,
minElev 0x05,
drLimit 0x00,
pDop 0xFA, 0x00,
tDop 0xFA, 0x00,
pAcc 0x64, 0x00,
tAcc 0x2C, 0x01,
staticHoldThresh 0x00,