Add radioDemodulator_F32 and associated examples

pull/16/merge
boblark 2 years ago
parent a6f329e36c
commit bf1cfa561a
  1. 1
      OpenAudio_ArduinoLibrary.h
  2. 104
      docs/index.html
  3. 332
      examples/FT8Receive/FT8Receive.ino
  4. BIN
      examples/FT8Receive/ProbFailureVsSNR.gnumeric
  5. 303
      examples/FT8Receive/Process_DSP_R.ino
  6. 474
      examples/FT8Receive/constantsR.ino
  7. 294
      examples/FT8Receive/decodeR.ino
  8. 290
      examples/FT8Receive/decode_ft8R.ino
  9. 211
      examples/FT8Receive/encodeR.ino
  10. 314
      examples/FT8Receive/ldpcR.ino
  11. 75
      examples/FT8Receive/locatorR.ino
  12. 78
      examples/FT8Receive/maidenheadR.ino
  13. 206
      examples/FT8Receive/textR.ino
  14. 400
      examples/FT8Receive/unpackR.ino
  15. 25
      examples/FT8Transmit/FT8Transmit.ino
  16. 347
      examples/FT8Transmit7/FT8Transmit7.ino
  17. 348
      examples/FT8Transmit7HP/FT8Transmit7HP.ino
  18. BIN
      gui/DesignTool_F32.zip
  19. 213
      radioFT8Demodulator_F32.cpp
  20. 407
      radioFT8Demodulator_F32.h

@ -58,6 +58,7 @@
#include "RadioFMDetector_F32.h"
#include "radioBFSKmodulator_F32.h"
#include "radioFT8Modulator_F32.h"
#include "radioFT8Demodulator_F32.h"
#include "RadioFMDiscriminator_F32.h"
#include "radioNoiseBlanker_F32.h"
#include "synth_sin_cos_f32.h"

@ -420,10 +420,8 @@ span.mainfunction {color: #993300; font-weight: bolder}
{"type":"radioBFSKModulator_F32","data":{"defaults":{"name":{"value":"new"}},"shortName":"BFSKMod","inputs":"0","output":"0","category":"radio-function","color":"#E6E0F8","icon":"arrow-in.png","outputs":"1"}},
{"type":"UART_F32","data":{"defaults":{"name":{"value":"new"}},"shortName":"UART","inputs":"1","output":"0","category":"radio-function","color":"#E6E0F8","icon":"arrow-in.png","outputs":"0"}},
{"type":"radioFT8Modulator_F32","data":{"defaults":{"name":{"value":"new"}},"shortName":"FT8Mod","inputs":"0","output":"0","category":"radio-function","color":"#E6E0F8","icon":"arrow-in.png","outputs":"1"}},
{"type":"radioFT8Demodulator_F32","data":{"defaults":{"name":{"value":"new"}},"shortName":"FT8Demod","inputs":"1","output":"0","category":"radio-function","color":"#E6E0F8","icon":"arrow-in.png","outputs":"0"}},
{"type":"RadioIQMixer_F32","data":{"defaults":{"name":{"value":"new"}},"shortName":"I-QMixer","inputs":"2","output":"0","category":"radio-function","color":"#E6E0F8","icon":"arrow-in.png","outputs":"2"}},
{"type":"AudioControlSGTL5000","data":{"defaults":{"name":{"value":"new"}},"shortName":"sgtl5000","inputs":0,"outputs":0,"category":"control-function","color":"#E6E0F8","icon":"arrow-in.png"}},
@ -3406,7 +3404,6 @@ The actual packets are taken
</script>
<script type="text/x-red" data-help-name="radioFT8Modulator_F32">
<!-- ============ radioFT8Modulator_F32 ========= -->
<h3>Summary</h3>
@ -3483,8 +3480,9 @@ The actual packets are taken
</p>
<h3>Examples</h3>
<p class=exam>File &gt; Examples &gt; OpenAudio_ArduinoLibrary &gt; FT8Transmit
</p>
<p class=exam>File &gt; Examples &gt; OpenAudio_ArduinoLibrary &gt; FT8Transmit</p>
<p class=exam>File &gt; Examples &gt; OpenAudio_ArduinoLibrary &gt; FT8Transmit7</p>
<p class=exam>File &gt; Examples &gt; OpenAudio_ArduinoLibrary &gt; FT8Transmit7HP</p>
<h3>Notes</h3>
<p>See the library file radioFT8Modulator.h for much more information,
@ -3504,6 +3502,100 @@ The actual packets are taken
</div>
</script>
<script type="text/x-red" data-help-name="radioFT8Demodulator_F32">
<!-- ============ radioFT8Demodulator_F32 ========= -->
<h3>Summary</h3>
<div class=tooltipinfo>
<p>Receives audio, containing multiple FT8 signals, and bundles them
up into 2048 sample float arrays, ready for an FFT. The system audio
sample rate is decimated to 6400 Hz and high rejection filtering is
provided with a final audio upper limit at 2800 Hz.
The full data array is updated and available every 0.16 second
to support 50% overlap for FFT windowing. The class also includes a
broad-band power detector for noise measurement.
</p>
</div>
<h3>Audio Connections</h3>
<table class=doc align=center cellpadding=3>
<tr class=top><th>Port</th><th>Purpose</th></tr>
<tr class=odd><td align=center>In 0</td><td>FT8 receive audio</td></tr>
</table>
<h3>Functions</h3>
<p class=func><span class=keyword>setSampleRate_Hz</span>
(<strong>const float32_t</strong> &fs_Hz);</p>
<p class=desc>The two values are 48000.0 and 96000.0. </p>
<p class=func><span class=keyword>initialize</span>();</p>
<p class=desc>This computes several filters that are needed.</p>
<p class=func><span class=keyword>getDataPtr</span>()</p>
<p class=desc>Returns pointer to an array of 2048 float32_t (aka float)
holding latest received audio data. To support windowed FFT's,
this data provides 50% overlap. This means that, even though the
2048 data points require 0.32 seconds to acquire, a new set of data is
available every 0.16 seconds. </p>
<p class=func><span class=keyword>startDataCollect</span>();</p>
<p class=desc>Begins a 14.7 second data collection period with 194
2048 float data arrays being made available.
No return value.</p>
<p class=func><span class=keyword>cancelDataCollect</span>();</p>
<p class=desc>Cancels the 14.7 second data collection period.
No return value.</p>
<p class=func><span class=keyword>receivingData</span>();</p>
<p class=desc>Returns <strong>bool</strong> true if the 14.7 data collection
is in progress.</p>
<p class=func><span class=keyword>powerAvailable</span>();</p>
<p class=desc>See the next function. Returns <strong>bool</strong>
true if the power measurement is available. </p>
<p class=func><span class=keyword>readPower</span>();</p>
<p class=desc>Returns the dB power level <strong>once</strong>
per 128 samples at the 6.4kHz rate.
This can be used to provide a noise level measurement when signals are not
being transmitted. See the receive example listed below.</p>
<p>Note that there are other fuctions available to support the W5BAA 128-int
data transfer. The details are in the radioFT8Demodulator_F32.h file.
Use of those functions requires compiling with "#define W5BAA_INTERFACE" in
the .h file.</p>
<h3>Examples</h3>
<p class=exam>File &gt; Examples &gt; OpenAudio_ArduinoLibrary &gt; FT8Receive
</p>
<h3>Notes</h3>
<p>See the library file radioFT8Demodulator.h for much more information,
references, sample data, and most importantly, credits to the many contributors
upon which these FT8 library classes are based.</p>
<p> This class does not provide true (absolute) clock timing.
The startDataCollect() function
should be called when it is time for a new 15-sec receive period.</p>
<p>The receive example, along with the corresponding transmit examples
for radioFT8Modulator_F32, are complete basic capabilities, but
do not serve as a ham radio controller. The
<a href="https://github.com/WB2CBA/W5BAA-FT8-POCKET-TERMINAL"
target="_blank">W5BAA Pocket project</a>
https://github.com/WB2CBA/W5BAA-FT8-POCKET-TERMINAL
is an example of a complete control app. It does not use this library.</p>
</script>
<script type="text/x-red" data-template-name="radioFT8Demodulator_F32">
<div class="form-row">
<label for="node-input-name"><i class="fa fa-tag"></i> Name</label>
<input type="text" id="node-input-name" placeholder="Name">
</div>
</script>
<div>
<script type="text/x-red" data-help-name="radioModulatedGenerator_F32">
<!-- ============ radioModulatedGenerator_F32 ========= -->

@ -0,0 +1,332 @@
// FT8Receive.ino 13 Oct 2022 Bob Larkin, W7PUA
// Simple command-line reception of WSJT FT8 signals for
// amateur radio.
/*
* Huge thanks to Charlie Hill, W5BAA, for his Pocket FT8 work, much of which
* is the basis for this INO: https://github.com/Rotron/Pocket-FT8
* That work started from the "FT8 Decoding Library" by
* Karlis Goba: https://github.com/kgoba/ft8_lib and thank you to both
* contributors.
*/
/*
* See Examples/Teensy/TimeTeensy3.ino for
* example code illustrating Time library with Real Time Clock.
*/
/* This INO uses the Teensy F32 Audio Library interface to test
* the radioFT8Demodulator_F32 data collector. This should
* not be used with "#define W5BAA_INTERFACE" in the file
* radioFT8Demodulator_F32.h, as that interface is different.
*/
/* The F32 Audio library class, radioFT8Demodulator_F32, performs the
* data collection and organization for FT8 reception. This occurs
* after every 128 audio samples, automatically. The sync and decode
* functions are time intensive and therefore not done with the audio
* interrupts. A complete set of Karlis Goba FT8 reception files is
* included with this INO and have been slightly renamed with an "R"
* at the end. The Goba functions have stayed the same and minimal
* changes are made to the functions.
*
* IMPORTANT -When one wants to build a full transmit and receive
* FT8 INO, maybe with waterfall, they should go back to the Goba and
* Hill files referenced above. This INO is intended as a minimal demonstration
* of FT8 reception with emphasis on testing the radioFT8Demodulator_F32
* class. That said, be aware that these receive files include
* snr estimation not available from the other sets.
*/
#include "Arduino.h"
#include <TimeLib.h>
#include <OpenAudio_ArduinoLibrary.h> // Added for F32 Teensy library RSL
#include <Audio.h>
#include "AudioStream.h"
#include "arm_math.h"
// The following debugging print dumps are available:
// DEBUG1 - Main INO and overall control
// DEBUG_N - Noise measurement data for snr estimates
// DEBUG_D - Decode measurements
// Uncomment the following for debugging:
// #define DEBUG1
// #define DEBUG_N
// #define DEBUG_D
#define FFT_SIZE 2048
#define block_size 128
#define input_gulp_size 1024
#define HIGH_FREQ_INDEX 368
#define LOW_FREQ_INDEX 48
#define FT8_FREQ_SPACING 6.25 // ??
#define ft8_min_freq FT8_FREQ_SPACING * LOW_FREQ_INDEX
#define ft8_msg_samples 92
// Alternate interface format.
// #define W5BAA
// Only 48 and 96 kHz audio sample rates are currently supported.
const float32_t sample_rate_Hz = 48000.0f;
const int audio_block_samples = 128;
AudioSettings_F32 audio_settings(sample_rate_Hz, audio_block_samples);
AudioInputI2S_F32 audioInI2S1(audio_settings); //xy=100,150
AudioEffectGain_F32 gain1; //xy=250,150
AudioAnalyzePeak_F32 peak1; //xy=400,250
radioFT8Demodulator_F32 demod1; //xy=400,150
AudioConnection_F32 patchCord1(audioInI2S1, 0, gain1, 0);
AudioConnection_F32 patchCord2(gain1, demod1);
AudioConnection_F32 patchCord3(gain1, peak1);
AudioControlSGTL5000 sgtl5000_1; //xy=100,250
// This is the big file of log powers
uint8_t export_fft_power[ft8_msg_samples*HIGH_FREQ_INDEX*4] ;
// Pointer to 2048 float data for FFT array in radioDemodulator_F32
float32_t* pData2K = NULL;
float32_t noisePowerEstimateL = 0.0f; // Works when big signals are absent
int16_t noisePwrDBIntL = 0;
float32_t noisePowerEstimateH = 0.0f; // Works for big signals and QRMt
int16_t noisePwrDBIntH = 0;
float32_t noisePeakAveRatio = 0.0f; // > about 100 for big sigs
// /char Station_Call[11]; //six character call sign + /0
// /char home_Locator[11];; // four character locator + /0
// /char Locator[11]; // four character locator + /0
char Station_Call[11]; // six character call sign + /0
char home_Locator[11]; // four character locator + /0
char Locator[11]; // four character locator + /0
uint16_t currentFrequency;
// Next 3 lines were uint32_t Sept 22 change to allow tOffset
int32_t current_time, start_time, ft8_time, ft8_mod_time, ft8_mod_time_last;
int32_t days_fraction, hours_fraction, minute_fraction;
int32_t tOffset = 0; // Added Sept 22
uint8_t ft8_hours, ft8_minutes, ft8_seconds;
int ft8_flag, FT_8_counter, ft8_marker, decode_flag;
int num_decoded_msg;
int xmit_flag, ft8_xmit_counter, Transmit_Armned;
int DSP_Flag; // =1 if new data is ready for FFT
int master_decoded;
// rcvFT8State
#define FT8_RCV_IDLE 0
#define FT8_RCV_DATA_COLLECT 1
#define FT8_RCV_FIND_POWERS 2
#define FT8_RCV_DECODE 3
int rcvFT8State = FT8_RCV_IDLE;
int master_offset, offset_step;
int Target_Flag = 0;
//From gen_ft8.cpp
char Target_Call[7]; //six character call sign + /0
char Target_Locator[5]; // four character locator + /0
int Target_RSL; // four character RSL + /0
// Define FT8 symbol counts
int ND = 58;
int NS = 21;
int NN = 79;
// Define the LDPC sizes
int N = 174;
int K = 91;
int M = 83;
int K_BYTES = 12;
// Define CRC parameters
uint16_t CRC_POLYNOMIAL = 0X2757; // CRC-14 polynomial without the leading (MSB) 1
int CRC_WIDTH = 14;
// Communicate amongst decode functions:
typedef struct Candidate {
int16_t score;
int16_t time_offset;
int16_t freq_offset;
uint8_t time_sub;
uint8_t freq_sub;
uint8_t alt; // Added for convenience Teensy, RSL
float32_t syncPower; // Added for Teensy, RSL
} Candidate;
uint8_t secLast = 0;
const int ledPin = 13;
bool showPower = false;
uint32_t tp = 0;
uint32_t tu;
uint32_t ct=0;
void setup(void) {
// set the Time library to use Teensy 4.x's RTC to keep time
setSyncProvider(getTeensy3Time);
AudioMemory_F32(50, audio_settings);
Serial.begin(9600);
delay(1000);
// Enable the audio shield, select input, and enable output
sgtl5000_1.enable();
sgtl5000_1.inputSelect(AUDIO_INPUT_LINEIN);
#ifndef W5BAA
pData2K = demod1.getDataPtr(); // 2048 floats in radioFT8Demodulator_F32
#endif
demod1.initialize();
demod1.setSampleRate_Hz(48000.0f);
init_DSP();
gain1.setGain(1.0);
update_synchronization();
Serial.println("FT8 Receive test");
if (timeStatus()!= timeSet)
Serial.println("Unable to sync with the RTC");
else
Serial.println("RTC has set the system time");
//demod1.startDataCollect(); NOT FOR W5BAA interface
}
void loop(void) {
int16_t inCmd;
if( Serial.available() )
{
inCmd = Serial.read();
if(inCmd=='=') //Set minute clock to zero
{
}
else if(inCmd=='p' || inCmd=='P') // Increase clock 0.1 sec
{
tOffset += 100;
Serial.println("Increase clock 0.1 sec");
Serial.println(0.001*(float)tOffset);
}
else if(inCmd=='l' || inCmd=='L') // Decrease clock 0.1 sec
{
tOffset -= 100;
Serial.println("Decrease clock 0.1 sec");
Serial.println(0.001*(float)tOffset);
}
else if(inCmd=='-') // Increase clock 1 sec
{
tOffset += 1000;
Serial.println("Increase clock 1 sec");
Serial.println(0.001*(float)tOffset);
}
else if(inCmd==',') // Decrease clock 1 sec
{
tOffset -= 1000;
Serial.println("Decrease clock 1 sec");
Serial.println(0.001*(float)tOffset);
}
else if(inCmd=='c' || inCmd=='C') // Clock display
{
Serial.print("Time Offset, millisecods = ");
Serial.println(tOffset);
}
else if(inCmd=='e' || inCmd=='E') // Toggle power display
{
showPower = !showPower;
Serial.print("Show Power = ");
Serial.println(showPower);
}
else if(inCmd=='?')
{
//Serial.println("= Set local FT-8 clock to 0 (60 sec range).");
Serial.println("p, P Increase local FT8 clock by 0.1 sec");
Serial.println("l, L Decrease local FT8 clock by 0.1 sec");
Serial.println("- Increase local FT8 clock by 1 sec");
Serial.println(", Decrease local FT8 clock by 1 sec");
Serial.println("c, C Display offset");
Serial.println("e, E Display received power");
Serial.println("? Help Display (this message)");
}
else if(inCmd>35) // Ignore anything below '#'
Serial.println("Cmd ???");
} // End, if Serial Available
// Print average power level to Serial Monitor
// Useful for testing and synchronizing the FT8 clock. Shows total band power.
if( showPower && demod1.powerAvailable() )
{
float32_t pwr=demod1.powerRead();
float32_t fl;
if(second()>secLast || (second()==0 && secLast==59))
{
secLast = second();
tp = millis();
}
fl = millis() + tOffset - start_time;
while(fl>=15000.0f)
fl -= 15000.0f;
Serial.print(0.001f*fl);
Serial.print(" ");
// Serial.print(0.001*(millis() - tp)+(float)second()); Serial.print(" ");
Serial.print(pwr); Serial.print(" ");
for(int jj=0; jj<2*(30-(int)(-0.5*pwr)); jj++)
Serial.print("*");
Serial.println();
}
update_synchronization();
ft8_mod_time = ft8_time%15000;
if( ft8_mod_time<100 && ft8_mod_time_last>14900 )
{
ft8_mod_time_last = ft8_mod_time;
rcvFT8State = FT8_RCV_DATA_COLLECT;
demod1.startDataCollect(); // Turn on decimation and data
#ifdef DEBUG1
Serial.println("= = = = = SYNC TIME 15 = = = = =");
#endif
digitalWrite(ledPin, HIGH); // set the LED on
delay(100);
digitalWrite(ledPin, LOW); // set the LED on
}
else
ft8_mod_time_last = ft8_mod_time;
if(rcvFT8State==FT8_RCV_DATA_COLLECT && demod1.available())
{
// Here every 80 mSec for FFT
rcvFT8State = FT8_RCV_FIND_POWERS;
// 1472 * 92 = 135424
//master_offset = offset_step * FT_8_counter; //offset_step=1472
master_offset = 736 * (demod1.getFFTCount() -1);
#ifdef DEBUG1
Serial.print("master offset = "); Serial.println(master_offset);
Serial.print("Extract Power, fft count = "); Serial.println( demod1.getFFTCount() );
#endif
extract_power(master_offset); // Do FFT and log powers
rcvFT8State = FT8_RCV_DATA_COLLECT;
#ifdef DEBUG1
Serial.println("Power array updated");
#endif
}
if(rcvFT8State!=FT8_RCV_IDLE && demod1.getFFTCount() >= 184)
{
rcvFT8State = FT8_RCV_DECODE;
#ifdef DEBUG1
Serial.println("FT8 Decode");
#endif
tu = micros();
num_decoded_msg = ft8_decode();
rcvFT8State = FT8_RCV_IDLE;
master_decoded = num_decoded_msg;
#ifdef DEBUG1
Serial.print("ft8_decode Time, uSec = ");
Serial.println(micros() - tu);
#endif
}
delay(1);
} // End loop()
time_t getTeensy3Time() {
return Teensy3Clock.get();
}
// This starts the receiving data collection every 15 sec
void update_synchronization() {
current_time = millis() + tOffset;
ft8_time = current_time - start_time;
ft8_hours = (int8_t)(ft8_time/3600000);
hours_fraction = ft8_time % 3600000;
ft8_minutes = (int8_t) (hours_fraction/60000);
ft8_seconds = (int8_t)((hours_fraction % 60000)/1000);
}

@ -0,0 +1,303 @@
/*
* Process_DSP_R.ino
* Basically the Hill code with changes for Teensy floating point
* OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* for the conversion to Teensy operation, as well as
* to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib.
* Thanks to all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (C) 2021, Charles Hill
Copyright (C) 2022, Bob Larkin on changes for F32 library
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.
*/
/* NOTE - The frequency range used here is the same as used by others.
* This is about bin 128 to 768, or 400 Hz to 2400 Hz.
* Stations do operate outside this range. It would be easy to
* increase the range here. The library function radioFT8Demodulator_F32 is filtered
* to pass all frequencies up to, at least 2800 Hz.
*/
// Following are used inside extract_power()
float32_t fft_buffer[2048];
float fftOutput[2048];
float window[2048]; // Change to 1024 by symmetry <<<<<<<<<<<<<<<<<<<
arm_rfft_fast_instance_f32 Sfft;
float32_t powerSum = 0.0f; // Use these for snr estimate
float32_t runningSum = 0.0f;
float32_t powerMax = 0.0f;
float32_t runningMax = 0.0f;
float32_t noiseBuffer[8]; // Circular storage
uint16_t noiseBufferWrite = 0; // Array index
bool noiseMeasured = false; // <<<<<<GLOBAL
uint8_t noisePower8 = 0; // half dB per noise estimate GLOBAL
void init_DSP(void) {
arm_rfft_fast_init_f32(&Sfft, 2048);
for (int i = 0; i < FFT_SIZE; ++i)
window[i] = ft_blackman_i(i, FFT_SIZE);
offset_step = 1472; // (int) HIGH_FREQ_INDEX*4; /// 1472
}
float ft_blackman_i(int i, int N) {
const float alpha = 0.16f; // or 2860/18608
const float a0 = (1 - alpha) / 2;
const float a1 = 1.0f / 2;
const float a2 = alpha / 2;
float x1 = cosf(2 * (float)M_PI * i / (N - 1));
//float x2 = cosf(4 * (float)M_PI * i / (N - 1));
float x2 = 2*x1*x1 - 1; // Use double angle formula
return a0 - a1*x1 + a2*x2;
}
// Compute FFT magnitudes (log power) for each timeslot in the signal
void extract_power( int offset) {
float32_t y[8];
float32_t noiseCoeff[3];
/* Format of export_fft_power[] array:
368 bytes of power for even time for 0.32 sec sample DESCRIBE BETTER <<<<<<<<<<<<<<<<<<<<<<
368 bytes of power for odd time for 0.32 sec sample
...
Repeated about 14.7/(0.08 sec) = 184 times. (Transmitted message length is 12.96 sec)
Total bytes 4 * 368 * 92 = 135424
The power byte is log encoded with a half dB MSB. This can handle a
dynamic range of 256/2 = 128 dB.
*/
for(int i=0; i<2048; i++)
{
fft_buffer[i] = window[i]*pData2K[i]; // Protect pData2K from in-place FFT (17 uSec)
}
// (float32_t* pIn, float32_t* pOut, uint8_t ifftFlag)
arm_rfft_fast_f32(&Sfft, fft_buffer, fftOutput, 0);
arm_cmplx_mag_squared_f32(fftOutput, fftOutput, 1024);
// Variables for estimating noise level for SNR
powerSum = 0.0f;
powerMax = 0.0f;
for(int i=1; i<1024; i++)
{
if(i>=128 && i<768) // Omit the first 400 Hz and last 800 Hz
powerSum += fftOutput[i];
if(fftOutput[i] > powerMax)
powerMax = fftOutput[i];
// Next, 20*log10() (not 10*) is to the make 8-bit resolution 0.5 dB.
// The floats range from nothing to 40*log10(1024)=120 for a
// pure sine wave. For FT8, we never encounter this. To keep
// the sine wave answer below 256 would use an upward
// offset of 256-120=136. This totally prevents overload!
// Borrow fft_buffer for a moment:
fft_buffer[i] = 136.0f + 20.0f*log10f( 0.0000001f + fftOutput[i] );
}
fft_buffer[0] = 0.000001; // Fake DC term
/* Noise needs to be estimated to determine snr. Two cases:
* runningMax/runningSum < 100 This is weak signal case for which
* the runningSum must be used alone.
* runningMax/runningSum > 100 Here the 2 second quiet period can
* can be found and running Sum used
* when runningMax/runningSum is high.
*/
runningSum = 0.80f*runningSum + 0.20f*powerSum; // Tracks changes in pwr
runningMax = 0.99f*runningMax + 0.01f*powerMax; // Slow decay
// Put the sum intocircular buffer
noiseBuffer[ 0X0007 & noiseBufferWrite++ ] = 0.00156f*runningSum;
for(int kk=0; kk<8; kk++)
y[kk] = (float32_t)noiseBuffer[ 0X0007 & (kk + noiseBufferWrite) ];
//fitCurve (int order, int nPoints, float32_t py[], int nCoeffs, float32_t *coeffs)
fitCurve(2, 8, y, 3, noiseCoeff);
float32_t y9 = noiseCoeff[2] + 9.0f*noiseCoeff[1] + 81.0f*noiseCoeff[0];
if(runningMax > 100.0f*0.00156f*runningSum && y9 > 2.0f*noiseCoeff[2] && !noiseMeasured)
{
// This measurement occurs once every 15 sec, but may be just before
// or just after decode. Either way, the "latest" noise estimate is used.
noiseMeasured = true; // Reset after decode()
noisePowerEstimateH = 0.2f*(y[0]+y[1]+y[2]+y[3]+y[4]);
noisePwrDBIntH = (int16_t)(10.0f*log10f(noisePowerEstimateH));
noisePeakAveRatio = runningMax/(0.00156*runningSum);
#ifdef DEBUG_N
Serial.println("Noise measurement between transmit time periods:");
Serial.print(" rSum, rMax= "); Serial.print(0.00156*runningSum, 5);
Serial.print(" "); Serial.print(runningMax, 5);
Serial.print(" Ratio= "); Serial.print(noisePeakAveRatio, 3);
Serial.print(" Int noise= ");
Serial.println(noisePwrDBIntH); // dB increments
#endif
}
// Loop over two frequency bin offsets. This first picks up 367 even
// numbered fft_buffer[] followed by 367 odd numbered bins. This is
// a frequency shift of 3.125 Hz. With windowing, the bandwidth
// of each FFT output is about 6 Hz, close to a match for the
// 0.16 sec transmission time.
/* First pass: j on (0, 367) j*2+freq_sub on (0, 734) (even)
* Secnd pass: j on (0, 367) j*2+freq_sub on (1, 735) (odd)
*/
for (int freq_sub=0; freq_sub<2; ++freq_sub)
{
for (int j=0; j<368; ++j)
{
export_fft_power[offset] = (uint8_t)fft_buffer[j*2 + freq_sub];
++offset;
}
}
} // End extract_power()
// ===============================================================
// CURVE FIT
/*
curveFitting - Library for fitting curves to given
points using Least Squares method, with Cramer's rule
used to solve the linear equation.
Created by Rowan Easter-Robinson, August 23, 2018.
Released into the public domain.
Converted to float32_t, made specific to FT8 case Bob L Oct 2022
*/
void cpyArray(float32_t *src, float32_t*dest, int n){
for (int i = 0; i < n*n; i++){
dest[i] = src[i];
}
}
void subCol(float32_t *mat, float32_t* sub, uint8_t coln, uint8_t n){
if (coln >= n) return;
for (int i = 0; i < n; i++){
mat[(i*n)+coln] = sub[i];
}
}
/*Determinant algorithm taken from
// https://codeforwin.org/2015/08/c-program-to-find-determinant-of-matrix.html */
int trianglize(float32_t **m, int n)
{
int sign = 1;
for (int i = 0; i < n; i++) {
int max = 0;
for (int row = i; row < n; row++)
if (fabs(m[row][i]) > fabs(m[max][i]))
max = row;
if (max) {
sign = -sign;
float32_t *tmp = m[i];
m[i] = m[max], m[max] = tmp;
}
if (!m[i][i]) return 0;
for (int row = i + 1; row < n; row++) {
float32_t r = m[row][i] / m[i][i];
if (!r) continue;
for (int col = i; col < n; col ++)
m[row][col] -= m[i][col] * r;
}
}
return sign;
}
float32_t det(float32_t *in, int n)
{
float32_t *m[n];
m[0] = in;
for (int i = 1; i < n; i++)
m[i] = m[i - 1] + n;
int sign = trianglize(m, n);
if (!sign)
return 0;
float32_t p = 1;
for (int i = 0; i < n; i++)
p *= m[i][i];
return p * sign;
}
/*End of Determinant algorithm*/
//Raise x to power
float32_t curveFitPower(float32_t base, int exponent){
if (exponent == 0){
return 1;
} else {
float32_t val = base;
for (int i = 1; i < exponent; i++){
val = val * base;
}
return val;
}
}
#define MAX_ORDER 4
int fitCurve (int order, int nPoints, float32_t py[], int nCoeffs, float32_t *coeffs) {
int i, j;
float32_t T[MAX_ORDER] = {0}; //Values to generate RHS of linear equation
float32_t S[MAX_ORDER*2+1] = {0}; //Values for LHS and RHS of linear equation
float32_t denom; //denominator for Cramer's rule, determinant of LHS linear equation
float32_t x, y;
float32_t px[nPoints]; //Generate X values, from 0 to n
for (i=0; i<nPoints; i++){
px[i] = i;
}
for (i=0; i<nPoints; i++) {//Generate matrix elements
x = px[i];
y = py[i];
for (j = 0; j < (nCoeffs*2)-1; j++){
S[j] += curveFitPower(x, j); // x^j iterated , S10 S20 S30 etc, x^0, x^1...
}
for (j = 0; j < nCoeffs; j++){
T[j] += y * curveFitPower(x, j); //y * x^j iterated, S01 S11 S21 etc, x^0*y, x^1*y, x^2*y...
}
}
float32_t masterMat[nCoeffs*nCoeffs]; //Master matrix LHS of linear equation
for (i = 0; i < nCoeffs ;i++){//index by matrix row each time
for (j = 0; j < nCoeffs; j++){//index within each row
masterMat[i*nCoeffs+j] = S[i+j];
}
}
float32_t mat[nCoeffs*nCoeffs]; //Temp matrix as det() method alters the matrix given
cpyArray(masterMat, mat, nCoeffs);
denom = det(mat, nCoeffs);
cpyArray(masterMat, mat, nCoeffs);
//Generate cramers rule mats
for (i = 0; i < nCoeffs; i++){ //Temporary matrix to substitute RHS of linear equation as per Cramer's rule
subCol(mat, T, i, nCoeffs);
coeffs[nCoeffs-i-1] = det(mat, nCoeffs)/denom; //Coefficients are det(M_i)/det(Master)
cpyArray(masterMat, mat, nCoeffs);
}
return 0;
}

@ -0,0 +1,474 @@
/*
* constantsR.ino
* Basically the Goba constants.h and .c with minor changes for Teensy
* Arduino use along with the floating point OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib
* and to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* as well as the all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (c) 2018 Kārlis Goba
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.
*/
#if 0
// Retained here as useful notes:
extern int K_BYTES;
extern uint8_t tones[79];
// Costas 7x7 tone pattern
extern const uint8_t kCostas_map[7];
// Gray code map
extern const uint8_t kGray_map[8];
// Parity generator matrix for (174,91) LDPC code, stored in bitpacked format (MSB first)
//extern const uint8_t kGenerator[M][K_BYTES];
extern uint8_t kGenerator[83][12];
// Column order (permutation) in which the bits in codeword are stored
// (Not really used in FT8 v2 - instead the Nm, Mn and generator matrices are already permuted)
//extern const uint8_t kColumn_order[N];
extern uint8_t kColumn_order[174];
// this is the LDPC(174,91) parity check matrix.
// 83 rows.
// each row describes one parity check.
// each number is an index into the codeword (1-origin).
// the codeword bits mentioned in each row must xor to zero.
// From WSJT-X's ldpc_174_91_c_reordered_parity.f90.
//extern const uint8_t kNm[M][7];
extern uint8_t kNm[83][7];
// Mn from WSJT-X's bpdecode174.f90.
// each row corresponds to a codeword bit.
// the numbers indicate which three parity
// checks (rows in Nm) refer to the codeword bit.
// 1-origin.
//extern const uint8_t kMn[N][3];
extern uint8_t kMn[174][3];
// Number of rows (columns in C/C++) in the array Nm.
//extern const uint8_t kNrw[M];
extern uint8_t kNrw[83];
#endif
// See FT8Receive.ino for defines of some constant values.
// Costas 7x7 tone pattern
const uint8_t kCostas_map[7] = { 3,1,4,0,6,5,2 };
// Gray code map
const uint8_t kGray_map[8] = { 0,1,3,2,5,6,4,7 };
// Parity generator matrix for (174,91) LDPC code, stored in bitpacked format (MSB first)
uint8_t kGenerator[83][12] = {
{ 0x83, 0x29, 0xce, 0x11, 0xbf, 0x31, 0xea, 0xf5, 0x09, 0xf2, 0x7f, 0xc0 },
{ 0x76, 0x1c, 0x26, 0x4e, 0x25, 0xc2, 0x59, 0x33, 0x54, 0x93, 0x13, 0x20 },
{ 0xdc, 0x26, 0x59, 0x02, 0xfb, 0x27, 0x7c, 0x64, 0x10, 0xa1, 0xbd, 0xc0 },
{ 0x1b, 0x3f, 0x41, 0x78, 0x58, 0xcd, 0x2d, 0xd3, 0x3e, 0xc7, 0xf6, 0x20 },
{ 0x09, 0xfd, 0xa4, 0xfe, 0xe0, 0x41, 0x95, 0xfd, 0x03, 0x47, 0x83, 0xa0 },
{ 0x07, 0x7c, 0xcc, 0xc1, 0x1b, 0x88, 0x73, 0xed, 0x5c, 0x3d, 0x48, 0xa0 },
{ 0x29, 0xb6, 0x2a, 0xfe, 0x3c, 0xa0, 0x36, 0xf4, 0xfe, 0x1a, 0x9d, 0xa0 },
{ 0x60, 0x54, 0xfa, 0xf5, 0xf3, 0x5d, 0x96, 0xd3, 0xb0, 0xc8, 0xc3, 0xe0 },
{ 0xe2, 0x07, 0x98, 0xe4, 0x31, 0x0e, 0xed, 0x27, 0x88, 0x4a, 0xe9, 0x00 },
{ 0x77, 0x5c, 0x9c, 0x08, 0xe8, 0x0e, 0x26, 0xdd, 0xae, 0x56, 0x31, 0x80 },
{ 0xb0, 0xb8, 0x11, 0x02, 0x8c, 0x2b, 0xf9, 0x97, 0x21, 0x34, 0x87, 0xc0 },
{ 0x18, 0xa0, 0xc9, 0x23, 0x1f, 0xc6, 0x0a, 0xdf, 0x5c, 0x5e, 0xa3, 0x20 },
{ 0x76, 0x47, 0x1e, 0x83, 0x02, 0xa0, 0x72, 0x1e, 0x01, 0xb1, 0x2b, 0x80 },
{ 0xff, 0xbc, 0xcb, 0x80, 0xca, 0x83, 0x41, 0xfa, 0xfb, 0x47, 0xb2, 0xe0 },
{ 0x66, 0xa7, 0x2a, 0x15, 0x8f, 0x93, 0x25, 0xa2, 0xbf, 0x67, 0x17, 0x00 },
{ 0xc4, 0x24, 0x36, 0x89, 0xfe, 0x85, 0xb1, 0xc5, 0x13, 0x63, 0xa1, 0x80 },
{ 0x0d, 0xff, 0x73, 0x94, 0x14, 0xd1, 0xa1, 0xb3, 0x4b, 0x1c, 0x27, 0x00 },
{ 0x15, 0xb4, 0x88, 0x30, 0x63, 0x6c, 0x8b, 0x99, 0x89, 0x49, 0x72, 0xe0 },
{ 0x29, 0xa8, 0x9c, 0x0d, 0x3d, 0xe8, 0x1d, 0x66, 0x54, 0x89, 0xb0, 0xe0 },
{ 0x4f, 0x12, 0x6f, 0x37, 0xfa, 0x51, 0xcb, 0xe6, 0x1b, 0xd6, 0xb9, 0x40 },
{ 0x99, 0xc4, 0x72, 0x39, 0xd0, 0xd9, 0x7d, 0x3c, 0x84, 0xe0, 0x94, 0x00 },
{ 0x19, 0x19, 0xb7, 0x51, 0x19, 0x76, 0x56, 0x21, 0xbb, 0x4f, 0x1e, 0x80 },
{ 0x09, 0xdb, 0x12, 0xd7, 0x31, 0xfa, 0xee, 0x0b, 0x86, 0xdf, 0x6b, 0x80 },
{ 0x48, 0x8f, 0xc3, 0x3d, 0xf4, 0x3f, 0xbd, 0xee, 0xa4, 0xea, 0xfb, 0x40 },
{ 0x82, 0x74, 0x23, 0xee, 0x40, 0xb6, 0x75, 0xf7, 0x56, 0xeb, 0x5f, 0xe0 },
{ 0xab, 0xe1, 0x97, 0xc4, 0x84, 0xcb, 0x74, 0x75, 0x71, 0x44, 0xa9, 0xa0 },
{ 0x2b, 0x50, 0x0e, 0x4b, 0xc0, 0xec, 0x5a, 0x6d, 0x2b, 0xdb, 0xdd, 0x00 },
{ 0xc4, 0x74, 0xaa, 0x53, 0xd7, 0x02, 0x18, 0x76, 0x16, 0x69, 0x36, 0x00 },
{ 0x8e, 0xba, 0x1a, 0x13, 0xdb, 0x33, 0x90, 0xbd, 0x67, 0x18, 0xce, 0xc0 },
{ 0x75, 0x38, 0x44, 0x67, 0x3a, 0x27, 0x78, 0x2c, 0xc4, 0x20, 0x12, 0xe0 },
{ 0x06, 0xff, 0x83, 0xa1, 0x45, 0xc3, 0x70, 0x35, 0xa5, 0xc1, 0x26, 0x80 },
{ 0x3b, 0x37, 0x41, 0x78, 0x58, 0xcc, 0x2d, 0xd3, 0x3e, 0xc3, 0xf6, 0x20 },
{ 0x9a, 0x4a, 0x5a, 0x28, 0xee, 0x17, 0xca, 0x9c, 0x32, 0x48, 0x42, 0xc0 },
{ 0xbc, 0x29, 0xf4, 0x65, 0x30, 0x9c, 0x97, 0x7e, 0x89, 0x61, 0x0a, 0x40 },
{ 0x26, 0x63, 0xae, 0x6d, 0xdf, 0x8b, 0x5c, 0xe2, 0xbb, 0x29, 0x48, 0x80 },
{ 0x46, 0xf2, 0x31, 0xef, 0xe4, 0x57, 0x03, 0x4c, 0x18, 0x14, 0x41, 0x80 },
{ 0x3f, 0xb2, 0xce, 0x85, 0xab, 0xe9, 0xb0, 0xc7, 0x2e, 0x06, 0xfb, 0xe0 },
{ 0xde, 0x87, 0x48, 0x1f, 0x28, 0x2c, 0x15, 0x39, 0x71, 0xa0, 0xa2, 0xe0 },
{ 0xfc, 0xd7, 0xcc, 0xf2, 0x3c, 0x69, 0xfa, 0x99, 0xbb, 0xa1, 0x41, 0x20 },
{ 0xf0, 0x26, 0x14, 0x47, 0xe9, 0x49, 0x0c, 0xa8, 0xe4, 0x74, 0xce, 0xc0 },
{ 0x44, 0x10, 0x11, 0x58, 0x18, 0x19, 0x6f, 0x95, 0xcd, 0xd7, 0x01, 0x20 },
{ 0x08, 0x8f, 0xc3, 0x1d, 0xf4, 0xbf, 0xbd, 0xe2, 0xa4, 0xea, 0xfb, 0x40 },
{ 0xb8, 0xfe, 0xf1, 0xb6, 0x30, 0x77, 0x29, 0xfb, 0x0a, 0x07, 0x8c, 0x00 },
{ 0x5a, 0xfe, 0xa7, 0xac, 0xcc, 0xb7, 0x7b, 0xbc, 0x9d, 0x99, 0xa9, 0x00 },
{ 0x49, 0xa7, 0x01, 0x6a, 0xc6, 0x53, 0xf6, 0x5e, 0xcd, 0xc9, 0x07, 0x60 },
{ 0x19, 0x44, 0xd0, 0x85, 0xbe, 0x4e, 0x7d, 0xa8, 0xd6, 0xcc, 0x7d, 0x00 },
{ 0x25, 0x1f, 0x62, 0xad, 0xc4, 0x03, 0x2f, 0x0e, 0xe7, 0x14, 0x00, 0x20 },
{ 0x56, 0x47, 0x1f, 0x87, 0x02, 0xa0, 0x72, 0x1e, 0x00, 0xb1, 0x2b, 0x80 },
{ 0x2b, 0x8e, 0x49, 0x23, 0xf2, 0xdd, 0x51, 0xe2, 0xd5, 0x37, 0xfa, 0x00 },
{ 0x6b, 0x55, 0x0a, 0x40, 0xa6, 0x6f, 0x47, 0x55, 0xde, 0x95, 0xc2, 0x60 },
{ 0xa1, 0x8a, 0xd2, 0x8d, 0x4e, 0x27, 0xfe, 0x92, 0xa4, 0xf6, 0xc8, 0x40 },
{ 0x10, 0xc2, 0xe5, 0x86, 0x38, 0x8c, 0xb8, 0x2a, 0x3d, 0x80, 0x75, 0x80 },
{ 0xef, 0x34, 0xa4, 0x18, 0x17, 0xee, 0x02, 0x13, 0x3d, 0xb2, 0xeb, 0x00 },
{ 0x7e, 0x9c, 0x0c, 0x54, 0x32, 0x5a, 0x9c, 0x15, 0x83, 0x6e, 0x00, 0x00 },
{ 0x36, 0x93, 0xe5, 0x72, 0xd1, 0xfd, 0xe4, 0xcd, 0xf0, 0x79, 0xe8, 0x60 },
{ 0xbf, 0xb2, 0xce, 0xc5, 0xab, 0xe1, 0xb0, 0xc7, 0x2e, 0x07, 0xfb, 0xe0 },
{ 0x7e, 0xe1, 0x82, 0x30, 0xc5, 0x83, 0xcc, 0xcc, 0x57, 0xd4, 0xb0, 0x80 },
{ 0xa0, 0x66, 0xcb, 0x2f, 0xed, 0xaf, 0xc9, 0xf5, 0x26, 0x64, 0x12, 0x60 },
{ 0xbb, 0x23, 0x72, 0x5a, 0xbc, 0x47, 0xcc, 0x5f, 0x4c, 0xc4, 0xcd, 0x20 },
{ 0xde, 0xd9, 0xdb, 0xa3, 0xbe, 0xe4, 0x0c, 0x59, 0xb5, 0x60, 0x9b, 0x40 },
{ 0xd9, 0xa7, 0x01, 0x6a, 0xc6, 0x53, 0xe6, 0xde, 0xcd, 0xc9, 0x03, 0x60 },
{ 0x9a, 0xd4, 0x6a, 0xed, 0x5f, 0x70, 0x7f, 0x28, 0x0a, 0xb5, 0xfc, 0x40 },
{ 0xe5, 0x92, 0x1c, 0x77, 0x82, 0x25, 0x87, 0x31, 0x6d, 0x7d, 0x3c, 0x20 },
{ 0x4f, 0x14, 0xda, 0x82, 0x42, 0xa8, 0xb8, 0x6d, 0xca, 0x73, 0x35, 0x20 },
{ 0x8b, 0x8b, 0x50, 0x7a, 0xd4, 0x67, 0xd4, 0x44, 0x1d, 0xf7, 0x70, 0xe0 },
{ 0x22, 0x83, 0x1c, 0x9c, 0xf1, 0x16, 0x94, 0x67, 0xad, 0x04, 0xb6, 0x80 },
{ 0x21, 0x3b, 0x83, 0x8f, 0xe2, 0xae, 0x54, 0xc3, 0x8e, 0xe7, 0x18, 0x00 },
{ 0x5d, 0x92, 0x6b, 0x6d, 0xd7, 0x1f, 0x08, 0x51, 0x81, 0xa4, 0xe1, 0x20 },
{ 0x66, 0xab, 0x79, 0xd4, 0xb2, 0x9e, 0xe6, 0xe6, 0x95, 0x09, 0xe5, 0x60 },
{ 0x95, 0x81, 0x48, 0x68, 0x2d, 0x74, 0x8a, 0x38, 0xdd, 0x68, 0xba, 0xa0 },
{ 0xb8, 0xce, 0x02, 0x0c, 0xf0, 0x69, 0xc3, 0x2a, 0x72, 0x3a, 0xb1, 0x40 },
{ 0xf4, 0x33, 0x1d, 0x6d, 0x46, 0x16, 0x07, 0xe9, 0x57, 0x52, 0x74, 0x60 },
{ 0x6d, 0xa2, 0x3b, 0xa4, 0x24, 0xb9, 0x59, 0x61, 0x33, 0xcf, 0x9c, 0x80 },
{ 0xa6, 0x36, 0xbc, 0xbc, 0x7b, 0x30, 0xc5, 0xfb, 0xea, 0xe6, 0x7f, 0xe0 },
{ 0x5c, 0xb0, 0xd8, 0x6a, 0x07, 0xdf, 0x65, 0x4a, 0x90, 0x89, 0xa2, 0x00 },
{ 0xf1, 0x1f, 0x10, 0x68, 0x48, 0x78, 0x0f, 0xc9, 0xec, 0xdd, 0x80, 0xa0 },
{ 0x1f, 0xbb, 0x53, 0x64, 0xfb, 0x8d, 0x2c, 0x9d, 0x73, 0x0d, 0x5b, 0xa0 },
{ 0xfc, 0xb8, 0x6b, 0xc7, 0x0a, 0x50, 0xc9, 0xd0, 0x2a, 0x5d, 0x03, 0x40 },
{ 0xa5, 0x34, 0x43, 0x30, 0x29, 0xea, 0xc1, 0x5f, 0x32, 0x2e, 0x34, 0xc0 },
{ 0xc9, 0x89, 0xd9, 0xc7, 0xc3, 0xd3, 0xb8, 0xc5, 0x5d, 0x75, 0x13, 0x00 },
{ 0x7b, 0xb3, 0x8b, 0x2f, 0x01, 0x86, 0xd4, 0x66, 0x43, 0xae, 0x96, 0x20 },
{ 0x26, 0x44, 0xeb, 0xad, 0xeb, 0x44, 0xb9, 0x46, 0x7d, 0x1f, 0x42, 0xc0 },
{ 0x60, 0x8c, 0xc8, 0x57, 0x59, 0x4b, 0xfb, 0xb5, 0x5d, 0x69, 0x60, 0x00 }
};
// Column order (permutation) in which the bits in codeword are stored
// (Not really used in FT8 v2 - instead the Nm, Mn and generator matrices are already permuted)
uint8_t kColumn_order[174] = {
0, 1, 2, 3, 28, 4, 5, 6, 7, 8, 9, 10, 11, 34, 12, 32, 13, 14, 15, 16,
17, 18, 36, 29, 43, 19, 20, 42, 21, 40, 30, 37, 22, 47, 61, 45, 44, 23, 41, 39,
49, 24, 46, 50, 48, 26, 31, 33, 51, 38, 52, 59, 55, 66, 57, 27, 60, 35, 54, 58,
25, 56, 62, 64, 67, 69, 63, 68, 70, 72, 65, 73, 75, 74, 71, 77, 78, 76, 79, 80,
53, 81, 83, 82, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99,
100,101,102,103,104,105,106,107,108,109,110,111,112,113,114,115,116,117,118,119,
120,121,122,123,124,125,126,127,128,129,130,131,132,133,134,135,136,137,138,139,
140,141,142,143,144,145,146,147,148,149,150,151,152,153,154,155,156,157,158,159,
160,161,162,163,164,165,166,167,168,169,170,171,172,173
};
// this is the LDPC(174,91) parity check matrix.
// 83 rows.
// each row describes one parity check.
// each number is an index into the codeword (1-origin).
// the codeword bits mentioned in each row must xor to zero.
// From WSJT-X's ldpc_174_91_c_reordered_parity.f90.
uint8_t kNm[83][7] = {
{ 4, 31, 59, 91, 92, 96, 153 },
{ 5, 32, 60, 93, 115, 146, 0 },
{ 6, 24, 61, 94, 122, 151, 0 },
{ 7, 33, 62, 95, 96, 143, 0 },
{ 8, 25, 63, 83, 93, 96, 148 },
{ 6, 32, 64, 97, 126, 138, 0 },
{ 5, 34, 65, 78, 98, 107, 154 },
{ 9, 35, 66, 99, 139, 146, 0 },
{ 10, 36, 67, 100, 107, 126, 0 },
{ 11, 37, 67, 87, 101, 139, 158 },
{ 12, 38, 68, 102, 105, 155, 0 },
{ 13, 39, 69, 103, 149, 162, 0 },
{ 8, 40, 70, 82, 104, 114, 145 },
{ 14, 41, 71, 88, 102, 123, 156 },
{ 15, 42, 59, 106, 123, 159, 0 },
{ 1, 33, 72, 106, 107, 157, 0 },
{ 16, 43, 73, 108, 141, 160, 0 },
{ 17, 37, 74, 81, 109, 131, 154 },
{ 11, 44, 75, 110, 121, 166, 0 },
{ 45, 55, 64, 111, 130, 161, 173 },
{ 8, 46, 71, 112, 119, 166, 0 },
{ 18, 36, 76, 89, 113, 114, 143 },
{ 19, 38, 77, 104, 116, 163, 0 },
{ 20, 47, 70, 92, 138, 165, 0 },
{ 2, 48, 74, 113, 128, 160, 0 },
{ 21, 45, 78, 83, 117, 121, 151 },
{ 22, 47, 58, 118, 127, 164, 0 },
{ 16, 39, 62, 112, 134, 158, 0 },
{ 23, 43, 79, 120, 131, 145, 0 },
{ 19, 35, 59, 73, 110, 125, 161 },
{ 20, 36, 63, 94, 136, 161, 0 },
{ 14, 31, 79, 98, 132, 164, 0 },
{ 3, 44, 80, 124, 127, 169, 0 },
{ 19, 46, 81, 117, 135, 167, 0 },
{ 7, 49, 58, 90, 100, 105, 168 },
{ 12, 50, 61, 118, 119, 144, 0 },
{ 13, 51, 64, 114, 118, 157, 0 },
{ 24, 52, 76, 129, 148, 149, 0 },
{ 25, 53, 69, 90, 101, 130, 156 },
{ 20, 46, 65, 80, 120, 140, 170 },
{ 21, 54, 77, 100, 140, 171, 0 },
{ 35, 82, 133, 142, 171, 174, 0 },
{ 14, 30, 83, 113, 125, 170, 0 },
{ 4, 29, 68, 120, 134, 173, 0 },
{ 1, 4, 52, 57, 86, 136, 152 },
{ 26, 51, 56, 91, 122, 137, 168 },
{ 52, 84, 110, 115, 145, 168, 0 },
{ 7, 50, 81, 99, 132, 173, 0 },
{ 23, 55, 67, 95, 172, 174, 0 },
{ 26, 41, 77, 109, 141, 148, 0 },
{ 2, 27, 41, 61, 62, 115, 133 },
{ 27, 40, 56, 124, 125, 126, 0 },
{ 18, 49, 55, 124, 141, 167, 0 },
{ 6, 33, 85, 108, 116, 156, 0 },
{ 28, 48, 70, 85, 105, 129, 158 },
{ 9, 54, 63, 131, 147, 155, 0 },
{ 22, 53, 68, 109, 121, 174, 0 },
{ 3, 13, 48, 78, 95, 123, 0 },
{ 31, 69, 133, 150, 155, 169, 0 },
{ 12, 43, 66, 89, 97, 135, 159 },
{ 5, 39, 75, 102, 136, 167, 0 },
{ 2, 54, 86, 101, 135, 164, 0 },
{ 15, 56, 87, 108, 119, 171, 0 },
{ 10, 44, 82, 91, 111, 144, 149 },
{ 23, 34, 71, 94, 127, 153, 0 },
{ 11, 49, 88, 92, 142, 157, 0 },
{ 29, 34, 87, 97, 147, 162, 0 },
{ 30, 50, 60, 86, 137, 142, 162 },
{ 10, 53, 66, 84, 112, 128, 165 },
{ 22, 57, 85, 93, 140, 159, 0 },
{ 28, 32, 72, 103, 132, 166, 0 },
{ 28, 29, 84, 88, 117, 143, 150 },
{ 1, 26, 45, 80, 128, 147, 0 },
{ 17, 27, 89, 103, 116, 153, 0 },
{ 51, 57, 98, 163, 165, 172, 0 },
{ 21, 37, 73, 138, 152, 169, 0 },
{ 16, 47, 76, 130, 137, 154, 0 },
{ 3, 24, 30, 72, 104, 139, 0 },
{ 9, 40, 90, 106, 134, 151, 0 },
{ 15, 58, 60, 74, 111, 150, 163 },
{ 18, 42, 79, 144, 146, 152, 0 },
{ 25, 38, 65, 99, 122, 160, 0 },
{ 17, 42, 75, 129, 170, 172, 0 }
};
// Mn from WSJT-X's bpdecode174.f90.
// each row corresponds to a codeword bit.
// the numbers indicate which three parity
// checks (rows in Nm) refer to the codeword bit.
// 1-origin.
uint8_t kMn[174][3] = {
{ 16, 45, 73 },
{ 25, 51, 62 },
{ 33, 58, 78 },
{ 1, 44, 45 },
{ 2, 7, 61 },
{ 3, 6, 54 },
{ 4, 35, 48 },
{ 5, 13, 21 },
{ 8, 56, 79 },
{ 9, 64, 69 },
{ 10, 19, 66 },
{ 11, 36, 60 },
{ 12, 37, 58 },
{ 14, 32, 43 },
{ 15, 63, 80 },
{ 17, 28, 77 },
{ 18, 74, 83 },
{ 22, 53, 81 },
{ 23, 30, 34 },
{ 24, 31, 40 },
{ 26, 41, 76 },
{ 27, 57, 70 },
{ 29, 49, 65 },
{ 3, 38, 78 },
{ 5, 39, 82 },
{ 46, 50, 73 },
{ 51, 52, 74 },
{ 55, 71, 72 },
{ 44, 67, 72 },
{ 43, 68, 78 },
{ 1, 32, 59 },
{ 2, 6, 71 },
{ 4, 16, 54 },
{ 7, 65, 67 },
{ 8, 30, 42 },
{ 9, 22, 31 },
{ 10, 18, 76 },
{ 11, 23, 82 },
{ 12, 28, 61 },
{ 13, 52, 79 },
{ 14, 50, 51 },
{ 15, 81, 83 },
{ 17, 29, 60 },
{ 19, 33, 64 },
{ 20, 26, 73 },
{ 21, 34, 40 },
{ 24, 27, 77 },
{ 25, 55, 58 },
{ 35, 53, 66 },
{ 36, 48, 68 },
{ 37, 46, 75 },
{ 38, 45, 47 },
{ 39, 57, 69 },
{ 41, 56, 62 },
{ 20, 49, 53 },
{ 46, 52, 63 },
{ 45, 70, 75 },
{ 27, 35, 80 },
{ 1, 15, 30 },
{ 2, 68, 80 },
{ 3, 36, 51 },
{ 4, 28, 51 },
{ 5, 31, 56 },
{ 6, 20, 37 },
{ 7, 40, 82 },
{ 8, 60, 69 },
{ 9, 10, 49 },
{ 11, 44, 57 },
{ 12, 39, 59 },
{ 13, 24, 55 },
{ 14, 21, 65 },
{ 16, 71, 78 },
{ 17, 30, 76 },
{ 18, 25, 80 },
{ 19, 61, 83 },
{ 22, 38, 77 },
{ 23, 41, 50 },
{ 7, 26, 58 },
{ 29, 32, 81 },
{ 33, 40, 73 },
{ 18, 34, 48 },
{ 13, 42, 64 },
{ 5, 26, 43 },
{ 47, 69, 72 },
{ 54, 55, 70 },
{ 45, 62, 68 },
{ 10, 63, 67 },
{ 14, 66, 72 },
{ 22, 60, 74 },
{ 35, 39, 79 },
{ 1, 46, 64 },
{ 1, 24, 66 },
{ 2, 5, 70 },
{ 3, 31, 65 },
{ 4, 49, 58 },
{ 1, 4, 5 },
{ 6, 60, 67 },
{ 7, 32, 75 },
{ 8, 48, 82 },
{ 9, 35, 41 },
{ 10, 39, 62 },
{ 11, 14, 61 },
{ 12, 71, 74 },
{ 13, 23, 78 },
{ 11, 35, 55 },
{ 15, 16, 79 },
{ 7, 9, 16 },
{ 17, 54, 63 },
{ 18, 50, 57 },
{ 19, 30, 47 },
{ 20, 64, 80 },
{ 21, 28, 69 },
{ 22, 25, 43 },
{ 13, 22, 37 },
{ 2, 47, 51 },
{ 23, 54, 74 },
{ 26, 34, 72 },
{ 27, 36, 37 },
{ 21, 36, 63 },
{ 29, 40, 44 },
{ 19, 26, 57 },
{ 3, 46, 82 },
{ 14, 15, 58 },
{ 33, 52, 53 },
{ 30, 43, 52 },
{ 6, 9, 52 },
{ 27, 33, 65 },
{ 25, 69, 73 },
{ 38, 55, 83 },
{ 20, 39, 77 },
{ 18, 29, 56 },
{ 32, 48, 71 },
{ 42, 51, 59 },
{ 28, 44, 79 },
{ 34, 60, 62 },
{ 31, 45, 61 },
{ 46, 68, 77 },
{ 6, 24, 76 },
{ 8, 10, 78 },
{ 40, 41, 70 },
{ 17, 50, 53 },
{ 42, 66, 68 },
{ 4, 22, 72 },
{ 36, 64, 81 },
{ 13, 29, 47 },
{ 2, 8, 81 },
{ 56, 67, 73 },
{ 5, 38, 50 },
{ 12, 38, 64 },
{ 59, 72, 80 },
{ 3, 26, 79 },
{ 45, 76, 81 },
{ 1, 65, 74 },
{ 7, 18, 77 },
{ 11, 56, 59 },
{ 14, 39, 54 },
{ 16, 37, 66 },
{ 10, 28, 55 },
{ 15, 60, 70 },
{ 17, 25, 82 },
{ 20, 30, 31 },
{ 12, 67, 68 },
{ 23, 75, 80 },
{ 27, 32, 62 },
{ 24, 69, 75 },
{ 19, 21, 71 },
{ 34, 53, 61 },
{ 35, 46, 47 },
{ 33, 59, 76 },
{ 40, 43, 83 },
{ 41, 42, 63 },
{ 49, 75, 83 },
{ 20, 44, 48 },
{ 42, 49, 57 }
};
uint8_t kNrw[83] = {
7,6,6,6,7,6,7,6,6,7,6,6,7,7,6,6,
6,7,6,7,6,7,6,6,6,7,6,6,6,7,6,6,
6,6,7,6,6,6,7,7,6,6,6,6,7,7,6,6,
6,6,7,6,6,6,7,6,6,6,6,7,6,6,6,7,
6,6,6,7,7,6,6,7,6,6,6,6,6,6,6,7,
6,6,6
};

@ -0,0 +1,294 @@
/*
* decodeR.ino
* Basically the Goba decode.h and .c with minor changes for Teensy
* Arduino use along with the floating point OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib
* and to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* as well as the all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (c) 2018 Kārlis Goba
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.
*/
/* CALL
int num_candidates = find_sync(export_fft_power,
ft8_msg_samples, HIGH_FREQ_INDEX, kCostas_map, kMax_candidates,
candidate_list, kMin_score);
*/
// Localize top N candidates in frequency and time according to their
// sync strength (looking at Costas symbols).
// We treat and organize the candidate list as a min-heap (empty initially).
// 92 368
int find_sync(const uint8_t *power, int num_blocks, int num_bins, // 40
const uint8_t *sync_map, int num_candidates, Candidate *heap, int min_score) {
int heap_size = 0;
const uint8_t *p8;
// Get a noise power estimate by averaging power[] values on a subset of the data.
// ToDo - Is the averaging of log values here adequate? Really should be
// power averaging, but that is time consuming.
// This is usd only when all signals are low in amplitude.
// Noise estimate takes about 145 uSec.
int npCount = 0;
float32_t np = 0.0f;
for(int jj=0; jj<368; jj += 4) // 0 to 367, inclusive, by 4's, 92 of them
{
for(int kk=48; kk<280; kk+=2)
{
np += (float32_t)power[jj*368+kk];
npCount++;
}
}
noisePowerEstimateL = np/(float32_t)npCount;
noisePwrDBIntL = (int16_t)(0.5f*noisePowerEstimateL);
#if DEBUG_N
Serial.println("Data for low SNR noise estimate:");
Serial.print(" Full Ave Noise = "); Serial.println(noisePowerEstimateL);
Serial.print(" Full Ave dB Noise Int = "); Serial.println(noisePwrDBIntL);
Serial.print(" Noise Sample Count = "); Serial.println(npCount);
#endif
// Here we allow time offsets that exceed signal boundaries, as long as we still have all data bits.
// I.e. we can afford to skip the first 7 or the last 7 Costas symbols, as long as we track how many
// sync symbols we included in the score, so the score is averaged.
// This sync search takes about 27 milliseconds
for (int alt = 0; alt < 4; ++alt)
{
// 92-79+7=20
for (int time_offset = -7; time_offset < num_blocks - NN + 7; ++time_offset) // NN=79
{
// 48 368-8=360
for (int freq_offset = LOW_FREQ_INDEX; freq_offset < num_bins - 8; ++freq_offset)
{
// There are about 33,000 combinations of time and frquency offsets
// because we don't know the frequency and there may be time errors.
// For each of these we find average sync score over sync
// symbols (m+k = 0-7, 36-43, 72-79)
int score = 0; // 32-bit int
int num_symbols = 0;
for (int m = 0; m <= 72; m += 36) // Over all 3 sync time groups of 7
{
for (int k = 0; k < 7; ++k) // Over all 7 symbols (in time)
{
// Check for time boundaries
if (time_offset + k + m < 0) continue;
if (time_offset + k + m >= num_blocks) break;
int offset = ((time_offset + k + m) * 4 + alt) * num_bins + freq_offset;
p8 = power + offset;
// const uint8_t kCostas_map[7] = { 3,1,4,0,6,5,2 }; i.e., sync_map[]
score += 8 * p8[sync_map[k]] -
p8[0] - p8[1] - p8[2] - p8[3] -
p8[4] - p8[5] - p8[6] - p8[7];
/*
// Check only the neighbors of the expected symbol frequency- and time-wise
int sm = sync_map[k]; // Index of the expected bin
if (sm > 0) {
// look at one frequency bin lower
score += p8[sm] - p8[sm - 1];
}
if (sm < 7) {
// look at one frequency bin higher
score += p8[sm] - p8[sm + 1];
}
if (k > 0) {
// look one symbol back in time
score += p8[sm] - p8[sm - 4 * num_bins];
}
if (k < 6) {
// look one symbol forward in time
score += p8[sm] - p8[sm + 4 * num_bins];
}
*/
++num_symbols;
}
}
score /= num_symbols;
// Todo - can this benefit from doing score in float?
//Serial.print("num_symbols "); Serial.println(num_symbols);
//Serial.print("score "); Serial.println(score);
// if(score > max_score) max_score = score;
if (score < min_score)
continue;
// If the heap is full AND the current candidate is better than
// the worst in the heap, we remove the worst and make space
if (heap_size == num_candidates && score > heap[0].score)
{
heap[0] = heap[heap_size - 1];
--heap_size;
heapify_down(heap, heap_size);
}
// If there's free space in the heap, we add the current candidate
if (heap_size < num_candidates)
{
heap[heap_size].score = score;
heap[heap_size].time_offset = time_offset;
heap[heap_size].freq_offset = freq_offset;
heap[heap_size].alt = alt; // Added for Teensy RSL
heap[heap_size].time_sub = alt / 2;
heap[heap_size].freq_sub = alt % 2;
heap[heap_size].syncPower = 0.0f; // Added for Teensy RSL
++heap_size;
heapify_up(heap, heap_size);
}
}
}
} //end of alt loop
// For the frequencies and times that match the candidates, go back to the power
// data and compute the power average over the 3 * 7 sync symbols
// For 20 candidates this takes about 340 uSec.
for(int hh=0; hh<heap_size; hh++)
{
// Compute syncPower over sync symbols (m+k = 0-7, 36-43, 72-79)
float32_t sPower = 0.0f;
int num_symbols = 0;
for (int m = 0; m <= 72; m += 36) // Over all 3 sync time groups of 7
{
for (int k = 0; k < 7; ++k) // Over all 7 symbols (in time)
{
// Check for time boundaries
if (heap[hh].time_offset + k + m < 0) continue;
if (heap[hh].time_offset + k + m >= num_blocks) break;
int offset = (heap[hh].time_offset + k + m) * 4 + heap[hh].alt*num_bins
+ heap[hh].freq_offset;
p8 = power + offset;
sPower += powf(10.0f, 0.05*(float32_t)(p8[sync_map[k]]-136));
++num_symbols;
}
}
heap[hh].syncPower = 10.0f*log10f(sPower/(float32_t)num_symbols); // This is a measure of signal power level in dB
}
return heap_size;
}
// Compute log likelihood log(p(1) / p(0)) of 174 message bits
// for later use in soft-decision LDPC decoding
// Takes about 28 uSec for each Candidate
void extract_likelihood(const uint8_t *power, int num_bins,
Candidate cand, const uint8_t *code_map,
float *log174) {
int ft8_offset = (cand.time_offset * 4 + cand.time_sub * 2 + cand.freq_sub)
*num_bins + cand.freq_offset;
// Go over FSK tones and skip Costas sync symbols
const int n_syms = 1;
// const int n_bits = 3 * n_syms;
// const int n_tones = (1 << n_bits);
for (int k = 0; k < ND; k += n_syms)
{
int sym_idx = (k < ND / 2) ? (k + 7) : (k + 14);
int bit_idx = 3 * k;
// Pointer to 8 bins of the current symbol
const uint8_t *ps = power + (ft8_offset + sym_idx * 4 * num_bins);
decode_symbol(ps, code_map, bit_idx, log174);
}
// Compute the variance of log174
float sum = 0;
float sum2 = 0;
float inv_n = 1.0f / N;
for (int i = 0; i < N; ++i)
{
sum += log174[i];
sum2 += log174[i] * log174[i];
}
float variance = (sum2 - sum * sum * inv_n) * inv_n;
// Normalize log174 such that sigma = 2.83 (Why? It's in WSJT-X, ft8b.f90)
// Seems to be 2.83 = sqrt(8). Experimentally sqrt(16) works better.
float norm_factor = sqrtf(16.0f / variance);
for (int i = 0; i < N; ++i)
{
log174[i] *= norm_factor;
}
}
static float max2(float a, float b) {
return (a >= b) ? a : b;
}
static float max4(float a, float b, float c, float d) {
return max2(max2(a, b), max2(c, d));
}
static void heapify_down(Candidate *heap, int heap_size) {
// heapify from the root down
int current = 0;
while (true)
{
int largest = current;
int left = 2 * current + 1;
int right = left + 1;
if (left < heap_size && heap[left].score < heap[largest].score)
largest = left;
if (right < heap_size && heap[right].score < heap[largest].score)
largest = right;
if (largest == current)
break;
Candidate tmp = heap[largest];
heap[largest] = heap[current];
heap[current] = tmp;
current = largest;
}
}
static void heapify_up(Candidate *heap, int heap_size) {
// heapify from the last node up
int current = heap_size - 1;
while (current > 0)
{
int parent = (current - 1)/ 2;
if (heap[current].score >= heap[parent].score)
break;
Candidate tmp = heap[parent];
heap[parent] = heap[current];
heap[current] = tmp;
current = parent;
}
}
// Compute unnormalized log likelihood log(p(1)/p(0)) of
// 3 message bits (1 FSK symbol)
static void decode_symbol(const uint8_t *power, const uint8_t *code_map,
int bit_idx, float *log174) {
// Cleaned up code for the simple case of n_syms==1
float s2[8];
for (int j = 0; j < 8; ++j)
{
s2[j] = (float)power[code_map[j]];
//s2[j] = (float)work_fft_power[offset+code_map[j]];
}
log174[bit_idx + 0] = max4(s2[4], s2[5], s2[6], s2[7]) - max4(s2[0], s2[1], s2[2], s2[3]);
log174[bit_idx + 1] = max4(s2[2], s2[3], s2[6], s2[7]) - max4(s2[0], s2[1], s2[4], s2[5]);
log174[bit_idx + 2] = max4(s2[1], s2[3], s2[5], s2[7]) - max4(s2[0], s2[2], s2[4], s2[6]);
}

@ -0,0 +1,290 @@
/*
* decode_ft8R.ino
* Basically the Goba decode_ft8.h and .c with minor changes for Teensy
* Arduino use along with the floating point OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib
* and to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* as well as the all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (c) 2018 Kārlis Goba
Modifications copyright 2022 Bob Larkin W7PUA
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.
*/
const int kLDPC_iterations = 10;
const int kMax_candidates = 40;
const int kMax_decoded_messages = 20;
const int kMax_message_length = 20;
const int kMin_score = 40; // Minimum sync score threshold for candidates
int validate_locator(char locator[]);
int strindex(char s[],char t[]);
typedef struct
{
char field1[14];
char field2[14];
char field3[7];
int freq_hz;
float32_t dTime; // Added Nov 2022
char decode_time[10];
int sync_score;
int snr;
int distance;
} Decode;
Decode new_decoded[20];
int num_calls; // number of unique calling stations
int num_call_checks;
int message_limit = 15;
// Moved out of ft8_decode
float freq_hz;
float32_t dt;
char rtc_string[10]; // print format stuff
int num_decoded;
char noiseType;
int ft8_decode(void) {
// decoded[] are temporary message stores for searching out duplicates
// Just use new_decoded[].field1, 2, and 3 ??
char decoded[kMax_decoded_messages][kMax_message_length];
const float fsk_dev = 6.25f; // tone spacing in Hz and symbol rate
Candidate candidate_list[kMax_candidates];
float log174[N];
uint8_t plain[N];
uint8_t a91[K_BYTES];
// Find top candidates by Costas sync score and localize them in time and frequency
int num_candidates = find_sync(export_fft_power,
ft8_msg_samples, HIGH_FREQ_INDEX, kCostas_map, kMax_candidates,
candidate_list, kMin_score);
// Go over candidates and attempt to decode messages
num_decoded = 0;
for (int idx = 0; idx < num_candidates; ++idx) {
Candidate cand = candidate_list[idx];
freq_hz = (cand.freq_offset + cand.freq_sub / 2.0f) * fsk_dev;
extract_likelihood(export_fft_power, HIGH_FREQ_INDEX, cand, kGray_map, log174);
// bp_decode() produces better decodes, uses way less memory
int n_errors = 0;
bp_decode(log174, kLDPC_iterations, plain, &n_errors);
if (n_errors > 0)
continue;
// Extract payload + CRC (first K bits)
pack_bits(plain, K, a91);
// Extract CRC and check it
uint16_t chksum = ((a91[9] & 0x07) << 11) | (a91[10] << 3) | (a91[11] >> 5);
a91[9] &= 0xF8;
a91[10] = 0;
a91[11] = 0;
uint16_t chksum2 = crc(a91, 96 - 14);
if (chksum != chksum2) continue; // Decode failed, around to start of loop again
char message[kMax_message_length];
char field1[14];
char field2[14];
char field3[7];
int rc = unpack77_fields(a91, field1, field2, field3);
if (rc < 0) continue; // Decode failed
sprintf(message,"%s %s %s ",field1, field2, field3);
// Check for duplicate messages (TODO: use hashing)
bool found = false;
int indexFound = -1;
for (int i = 0; i < num_decoded; ++i)
{
if (0 == strcmp(decoded[i], message))
{
found = true;
indexFound = i;
break;
}
}
float distance;
getTeensy3Time(); // MOVE OUT OF LOOP???? <<<<<<<<<<<<<<<<<<<<<<<<<<
sprintf( rtc_string, " %2i:%2i:%2i ", hour(), minute(), second() );
for(int kk=1; kk<9; kk++)
{
if(rtc_string[kk] == ' ')
rtc_string[kk] = '0';
}
dt = 0.16f*(float)cand.time_offset;
// Revised procedure to support snr measurement. Now keep the strongest
// of duplicates. Bob Larkin Nov 2020.
if(found) // Keep the one with bigger score, put into [
{
#ifdef DEBUG_D
Serial.print("cand.score = "); Serial.print(cand.score);
Serial.print(" candidate_list[indexFound].score = "); Serial.println(candidate_list[indexFound].score);
#endif
if(cand.score > candidate_list[indexFound].score)
{
#ifdef DEBUG_D
Serial.print("Replace "); Serial.print(indexFound);
Serial.print(" with "); Serial.println(num_decoded);
Serial.print("Old score = "); Serial.print(candidate_list[indexFound].score);
Serial.print(" New score = "); Serial.println(cand.score);
#endif
// .decode_time and field1, 2 and 3 are correct already
new_decoded[indexFound].sync_score = cand.score;
new_decoded[indexFound].freq_hz = (int)freq_hz;
new_decoded[indexFound].dTime = dt;
if(noisePeakAveRatio < 100.0f) // No big signals
{
new_decoded[indexFound].snr =
cand.syncPower - (float32_t)noisePwrDBIntL + 51.0f;
noiseType = 'L';
}
else
{
new_decoded[indexFound].snr =
cand.syncPower - (float32_t)noisePwrDBIntH - 13.0f;
noiseType = 'H';
}
if(new_decoded[indexFound].snr < -21)
new_decoded[indexFound].snr = -21; // It is never lower!!
// num_decoded is left unchanged
}
}
// !found means this is a new entry to add to decoded list
else // Duplicate not found
{
if(num_decoded < kMax_decoded_messages) // Make new entry if room
{
if(strlen(message) < kMax_message_length)
{
#ifdef DEBUG_D
Serial.print("Enter "); Serial.print(num_decoded);
Serial.print(rtc_string);
Serial.print("msg: ");
Serial.print(message);
#endif
strcpy(decoded[num_decoded], message);
new_decoded[num_decoded].sync_score = cand.score;
new_decoded[num_decoded].freq_hz = (int)freq_hz;
new_decoded[num_decoded].dTime = dt;
strcpy(new_decoded[num_decoded].field1, field1);
strcpy(new_decoded[num_decoded].field2, field2);
strcpy(new_decoded[num_decoded].field3, field3);
strcpy(new_decoded[num_decoded].decode_time, rtc_string);
if(noisePeakAveRatio < 100.0f) // No big signals for quiet timing
new_decoded[num_decoded].snr =
cand.syncPower - (float32_t)noisePwrDBIntL + 51.0f;
else
new_decoded[num_decoded].snr =
cand.syncPower - (float32_t)noisePwrDBIntH - 13.0f;
if(new_decoded[num_decoded].snr < -21)
new_decoded[num_decoded].snr = -21; // It is never lower!!
#ifdef DEBUG_D
Serial.print(" dt="); Serial.print(0.16f*(float)cand.time_offset); // secs
Serial.print(" freq="); Serial.print((int)freq_hz);
Serial.print(" snr="); Serial.println(new_decoded[num_decoded].snr);
#endif
#ifdef DEBUG_N
Serial.print("syncPower, noiseL, noiseH, ratio { "); Serial.print(cand.syncPower, 1);
Serial.print(" "); Serial.print(noisePwrDBIntL);
Serial.print(" "); Serial.print(noisePwrDBIntH);
Serial.print(" "); Serial.print(noisePeakAveRatio, 1);
Serial.println(" }");
#endif
char Target_Locator[] = " ";
strcpy(Target_Locator, new_decoded[num_decoded].field3);
if (validate_locator(Target_Locator) == 1)
{
distance = Target_Distance(Target_Locator);
new_decoded[num_decoded].distance = (int)distance;
}
else
{
new_decoded[num_decoded].distance = 0;
}
++num_decoded;
}
} // End, there was room for new entry
} // End, duplicate not found
} //End of big decode loop
noiseMeasured = false; // Global flag for Process_DSP_R
printFT8Received();
return num_decoded;
}
void printFT8Received(void) {
char message2[kMax_message_length];
Serial.print("FT8 Received TRansmissions, Noise Type=");
Serial.println(noiseType);
for(int kk=0; kk<num_decoded; kk++)
{
Serial.print(kk);
Serial.print(rtc_string);
Serial.print(" msg: ");
sprintf(message2,"%s %s %s ",new_decoded[kk].field1,
new_decoded[kk].field2, new_decoded[kk].field3);
Serial.print(message2);
Serial.print(" dt="); Serial.print(new_decoded[kk].dTime); // secs
Serial.print(" freq="); Serial.print(new_decoded[kk].freq_hz);
Serial.print(" snr="); Serial.println(new_decoded[kk].snr);
}
Serial.println("");
}
int validate_locator(char locator[]) {
uint8_t A1, A2, N1, N2;
uint8_t test = 0;
A1 = locator[0] - 65;
A2 = locator[1] - 65;
N1 = locator[2] - 48;
N2= locator [3] - 48;
if (A1 >= 0 && A1 <= 17) test++;
if (A2 > 0 && A2 < 17) test++; //block RR73 Artic and Anartica
if (N1 >= 0 && N1 <= 9) test++;
if (N2 >= 0 && N2 <= 9) test++;
if (test == 4) return 1;
else
return 0;
}
int strindex(char s[],char t[]) {
int i,j,k, result;
result = -1;
for(i=0; s[i]!='\0'; i++)
{
for(j=i,k=0; t[k]!='\0' && s[j]==t[k]; j++,k++)
;
if(k>0 && t[k] == '\0')
result = i;
}
return result;
}

@ -0,0 +1,211 @@
/*
* encodeR.ino
* Basically the Goba encode.h and .c with minor changes for Teensy
* Arduino use along with the floating point OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib
* and to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* as well as the all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (c) 2018 Kārlis Goba
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.
*/
// This ino is needed for transmit FT8, but in order to get crc(),
// it is needed for receive also.
#if 0
// REMOVE FOR RECEIVE ONLY FILE
// Returns 1 if an odd number of bits are set in x, zero otherwise
uint8_t parity8(uint8_t x) {
x ^= x >> 4; // a b c d ae bf cg dh
x ^= x >> 2; // a b ac bd cae dbf aecg bfdh
x ^= x >> 1; // a ab bac acbd bdcae caedbf aecgbfdh
return (x) & 1;
}
// Encode a 91-bit message and return a 174-bit codeword.
// The generator matrix has dimensions (87,87).
// The code is a (174,91) regular ldpc code with column weight 3.
// The code was generated using the PEG algorithm.
// Arguments:
// [IN] message - array of 91 bits stored as 12 bytes (MSB first)
// [OUT] codeword - array of 174 bits stored as 22 bytes (MSB first)
void encode174(const uint8_t *message, uint8_t *codeword) {
// Here we don't generate the generator bit matrix as in WSJT-X implementation
// Instead we access the generator bits straight from the binary representation in kGenerator
// For reference:
// codeword(1:K)=message
// codeword(K+1:N)=pchecks
// printf("Encode ");
// for (int i = 0; i < K_BYTES; ++i) {
// printf("%02x ", message[i]);
// }
// printf("\n");
// Fill the codeword with message and zeros, as we will only update binary ones later
for (int j = 0; j < (7 + N) / 8; ++j) {
codeword[j] = (j < K_BYTES) ? message[j] : 0;
}
uint8_t col_mask = (0x80 >> (K % 8)); // bitmask of current byte
uint8_t col_idx = K_BYTES - 1; // index into byte array
// Compute the first part of itmp (1:M) and store the result in codeword
for (int i = 0; i < M; ++i) { // do i=1,M
// Fast implementation of bitwise multiplication and parity checking
// Normally nsum would contain the result of dot product between message and kGenerator[i],
// but we only compute the sum modulo 2.
uint8_t nsum = 0;
for (int j = 0; j < K_BYTES; ++j) {
uint8_t bits = message[j] & kGenerator[i][j]; // bitwise AND (bitwise multiplication)
nsum ^= parity8(bits); // bitwise XOR (addition modulo 2)
}
// Check if we need to set a bit in codeword
if (nsum % 2) { // pchecks(i)=mod(nsum,2)
codeword[col_idx] |= col_mask;
}
col_mask >>= 1;
if (col_mask == 0) {
col_mask = 0x80;
++col_idx;
}
}
// printf("Result ");
// for (int i = 0; i < (N + 7) / 8; ++i) {
// printf("%02x ", codeword[i]);
// }
// printf("\n");
}
#endif
// Compute 14-bit CRC for a sequence of given number of bits
// [IN] message - byte sequence (MSB first)
// [IN] num_bits - number of bits in the sequence
uint16_t crc(uint8_t *message, int num_bits) {
// Adapted from https://barrgroup.com/Embedded-Systems/How-To/CRC-Calculation-C-Code
//constexpr uint16_t TOPBIT = (1 << (CRC_WIDTH - 1));
uint16_t TOPBIT = (1 << (CRC_WIDTH - 1));
// printf("CRC, %d bits: ", num_bits);
// for (int i = 0; i < (num_bits + 7) / 8; ++i) {
// printf("%02x ", message[i]);
// }
// printf("\n");
uint16_t remainder = 0;
int idx_byte = 0;
// Perform modulo-2 division, a bit at a time.
for (int idx_bit = 0; idx_bit < num_bits; ++idx_bit) {
if (idx_bit % 8 == 0) {
// Bring the next byte into the remainder.
remainder ^= (message[idx_byte] << (CRC_WIDTH - 8));
++idx_byte;
}
// Try to divide the current data bit.
if (remainder & TOPBIT) {
remainder = (remainder << 1) ^ CRC_POLYNOMIAL;
}
else {
remainder = (remainder << 1);
}
}
// printf("CRC = %04xh\n", remainder & ((1 << CRC_WIDTH) - 1));
return remainder & ((1 << CRC_WIDTH) - 1);
}
#if 0
// REMOVE FOR RECEIVE ONLY FILE
// Generate FT8 tone sequence from payload data
// [IN] payload - 10 byte array consisting of 77 bit payload (MSB first)
// [OUT] itone - array of NN (79) bytes to store the generated tones (encoded as 0..7)
void genft8(const uint8_t *payload, uint8_t *itone) {
uint8_t a91[12]; // Store 77 bits of payload + 14 bits CRC
// Copy 77 bits of payload data
for (int i = 0; i < 10; i++)
a91[i] = payload[i];
// Clear 3 bits after the payload to make 80 bits
a91[9] &= 0xF8;
a91[10] = 0;
a91[11] = 0;
// Calculate CRC of 12 bytes = 96 bits, see WSJT-X code
uint16_t checksum = crc(a91, 96 - 14);
// Store the CRC at the end of 77 bit message
a91[9] |= (uint8_t)(checksum >> 11);
a91[10] = (uint8_t)(checksum >> 3);
a91[11] = (uint8_t)(checksum << 5);
// a87 contains 77 bits of payload + 14 bits of CRC
uint8_t codeword[22];
encode174(a91, codeword);
// Message structure: S7 D29 S7 D29 S7
for (int i = 0; i < 7; ++i) {
itone[i] = kCostas_map[i];
itone[36 + i] = kCostas_map[i];
itone[72 + i] = kCostas_map[i];
}
int k = 7; // Skip over the first set of Costas symbols
uint8_t mask = 0x80;
int i_byte = 0;
for (int j = 0; j < ND; ++j) { // do j=1,ND
if (j == 29) {
k += 7; // Skip over the second set of Costas symbols
}
// Extract 3 bits from codeword at i-th position
uint8_t bits3 = 0;
if (codeword[i_byte] & mask) bits3 |= 4;
if (0 == (mask >>= 1)) { mask = 0x80; i_byte++; }
if (codeword[i_byte] & mask) bits3 |= 2;
if (0 == (mask >>= 1)) { mask = 0x80; i_byte++; }
if (codeword[i_byte] & mask) bits3 |= 1;
if (0 == (mask >>= 1)) { mask = 0x80; i_byte++; }
itone[k] = kGray_map[bits3];
++k;
}
}
#endif

@ -0,0 +1,314 @@
/*
* ldpcR.ino
* Basically the Goba ldpc.h and .c with minor changes for Teensy
* Arduino use along with the floating point OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib
* and to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* as well as the all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (c) 2018 Kārlis Goba
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.
*/
//
// LDPC decoder for FT8.
//
// given a 174-bit codeword as an array of log-likelihood of zero,
// return a 174-bit corrected codeword, or zero-length array.
// last 87 bits are the (systematic) plain-text.
// this is an implementation of the sum-product algorithm
// from Sarah Johnson's Iterative Error Correction book.
// codeword[i] = log ( P(x=0) / P(x=1) )
//
// Packs a string of bits each represented as a zero/non-zero byte in plain[],
// as a string of packed bits starting from the MSB of the first byte of packed[]
void pack_bits(const uint8_t plain[], int num_bits, uint8_t packed[]) {
int num_bytes = (num_bits + 7) / 8;
for (int i = 0; i < num_bytes; ++i) {
packed[i] = 0;
}
uint8_t mask = 0x80;
int byte_idx = 0;
for (int i = 0; i < num_bits; ++i) {
if (plain[i]) {
packed[byte_idx] |= mask;
}
mask >>= 1;
if (!mask) {
mask = 0x80;
++byte_idx;
}
}
}
// codeword is 174 log-likelihoods.
// plain is a return value, 174 ints, to be 0 or 1.
// max_iters is how hard to try.
// ok == 87 means success.
void ldpc_decode(float codeword[], int max_iters, uint8_t plain[], int *ok) {
float m[M][N]; // ~60 kB
float e[M][N]; // ~60 kB
int min_errors = M;
for (int j = 0; j < M; j++) {
for (int i = 0; i < N; i++) {
m[j][i] = codeword[i];
e[j][i] = 0.0f;
}
}
for (int iter = 0; iter < max_iters; iter++) {
for (int j = 0; j < M; j++) {
for (int ii1 = 0; ii1 < kNrw[j]; ii1++) {
int i1 = kNm[j][ii1] - 1;
float a = 1.0f;
for (int ii2 = 0; ii2 < kNrw[j]; ii2++) {
int i2 = kNm[j][ii2] - 1;
if (i2 != i1) {
a *= fast_tanh(-m[j][i2] / 2.0f);
}
}
e[j][i1] = logf((1 - a) / (1 + a));
}
}
for (int i = 0; i < N; i++) {
float l = codeword[i];
for (int j = 0; j < 3; j++)
l += e[kMn[i][j] - 1][i];
plain[i] = (l > 0) ? 1 : 0;
}
int errors = ldpc_check(plain);
if (errors < min_errors) {
// Update the current best result
min_errors = errors;
if (errors == 0) {
break; // Found a perfect answer
}
}
for (int i = 0; i < N; i++) {
for (int ji1 = 0; ji1 < 3; ji1++) {
int j1 = kMn[i][ji1] - 1;
float l = codeword[i];
for (int ji2 = 0; ji2 < 3; ji2++) {
if (ji1 != ji2) {
int j2 = kMn[i][ji2] - 1;
l += e[j2][i];
}
}
m[j1][i] = l;
}
}
}
*ok = min_errors;
}
//
// does a 174-bit codeword pass the FT8's LDPC parity checks?
// returns the number of parity errors.
// 0 means total success.
//
static int ldpc_check(uint8_t codeword[]) {
int errors = 0;
for (int j = 0; j < M; ++j) {
uint8_t x = 0;
for (int i = 0; i < kNrw[j]; ++i) {
x ^= codeword[kNm[j][i] - 1];
}
if (x != 0) {
++errors;
}
}
return errors;
}
void bp_decode(float codeword[], int max_iters, uint8_t plain[], int *ok) {
float tov[N][3];
float toc[M][7];
int min_errors = M;
// initialize messages to checks
for (int i = 0; i < M; ++i) {
for (int j = 0; j < kNrw[i]; ++j) {
toc[i][j] = codeword[kNm[i][j] - 1];
}
}
for (int i = 0; i < N; ++i) {
for (int j = 0; j < 3; ++j) {
tov[i][j] = 0;
}
}
for (int iter = 0; iter < max_iters; ++iter) {
float zn[N];
// Update bit log likelihood ratios (tov=0 in iter 0)
for (int i = 0; i < N; ++i) {
zn[i] = codeword[i] + tov[i][0] + tov[i][1] + tov[i][2];
plain[i] = (zn[i] > 0) ? 1 : 0;
}
// Check to see if we have a codeword (check before we do any iter)
int errors = ldpc_check(plain);
if (errors < min_errors) {
// we have a better guess - update the result
min_errors = errors;
if (errors == 0) {
break; // Found a perfect answer
}
}
// Send messages from bits to check nodes
for (int i = 0; i < M; ++i) {
for (int j = 0; j < kNrw[i]; ++j) {
int ibj = kNm[i][j] - 1;
toc[i][j] = zn[ibj];
for (int kk = 0; kk < 3; ++kk) {
// subtract off what the bit had received from the check
if (kMn[ibj][kk] - 1 == i) {
toc[i][j] -= tov[ibj][kk];
}
}
}
}
// send messages from check nodes to variable nodes
for (int i = 0; i < M; ++i) {
for (int j = 0; j < kNrw[i]; ++j) {
toc[i][j] = fast_tanh(-toc[i][j] / 2);
}
}
for (int i = 0; i < N; ++i) {
for (int j = 0; j < 3; ++j) {
int ichk = kMn[i][j] - 1; // kMn(:,j) are the checks that include bit j
float Tmn = 1.0f;
for (int k = 0; k < kNrw[ichk]; ++k) {
if (kNm[ichk][k] - 1 != i) {
Tmn *= toc[ichk][k];
}
}
tov[i][j] = 2 * fast_atanh(-Tmn);
}
}
}
*ok = min_errors;
}
// https://varietyofsound.wordpress.com/2011/02/14/efficient-tanh-computation-using-lamberts-continued-fraction/
// http://functions.wolfram.com/ElementaryFunctions/ArcTanh/10/0001/
// https://mathr.co.uk/blog/2017-09-06_approximating_hyperbolic_tangent.html
// thank you Douglas Bagnall
// https://math.stackexchange.com/a/446411
static float fast_tanh(float x) {
if (x < -4.97f) {
return -1.0f;
}
if (x > 4.97f) {
return 1.0f;
}
float x2 = x * x;
//float a = x * (135135.0f + x2 * (17325.0f + x2 * (378.0f + x2)));
//float b = 135135.0f + x2 * (62370.0f + x2 * (3150.0f + x2 * 28.0f));
//float a = x * (10395.0f + x2 * (1260.0f + x2 * 21.0f));
//float b = 10395.0f + x2 * (4725.0f + x2 * (210.0f + x2));
float a = x * (945.0f + x2 * (105.0f + x2));
float b = 945.0f + x2 * (420.0f + x2 * 15.0f);
return a / b;
}
static float fast_atanh(float x) {
float x2 = x * x;
//float a = x * (-15015.0f + x2 * (19250.0f + x2 * (-5943.0f + x2 * 256.0f)));
//float b = (-15015.0f + x2 * (24255.0f + x2 * (-11025.0f + x2 * 1225.0f)));
//float a = x * (-1155.0f + x2 * (1190.0f + x2 * -231.0f));
//float b = (-1155.0f + x2 * (1575.0f + x2 * (-525.0f + x2 * 25.0f)));
float a = x * (945.0f + x2 * (-735.0f + x2 * 64.0f));
float b = (945.0f + x2 * (-1050.0f + x2 * 225.0f));
return a / b;
}
/* Not used in FT8Receive.ino - maybe not at all?
static float pltanh(float x) {
float isign = +1;
if (x < 0) {
isign = -1;
x = -x;
}
if (x < 0.8f) {
return isign * 0.83 * x;
}
if (x < 1.6f) {
return isign * (0.322f * x + 0.4064f);
}
if (x < 3.0f) {
return isign * (0.0524f * x + 0.8378f);
}
if (x < 7.0f) {
return isign * (0.0012f * x + 0.9914f);
}
return isign*0.9998f;
}
static float platanh(float x) {
float isign = +1;
if (x < 0) {
isign = -1;
x = -x;
}
if (x < 0.664f) {
return isign * x / 0.83f;
}
if (x < 0.9217f) {
return isign * (x - 0.4064f) / 0.322f;
}
if (x < 0.9951f) {
return isign * (x - 0.8378f) / 0.0524f;
}
if (x < 0.9998f) {
return isign * (x - 0.9914f) / 0.0012f;
}
return isign * 7.0f;
}
*/

@ -0,0 +1,75 @@
/*
* locator.ino
*
* Created on: Nov 4, 2019
* Author: user
*/
//#include "locator.h"
//#include <math.h>
//#include "arm_math.h"
// TODO - Looks like single precision would be adequate - RSL
const double EARTH_RAD = 6371; //radius in km
//void process_locator(char locator[]);
//double distance(double lat1, double lon1, double lat2, double lon2);
//double deg2rad(double deg);
float Latitude, Longitude;
float Station_Latitude, Station_Longitude;
float Target_Latitude, Target_Longitude;
//float Target_Distance(char target[]);
void set_Station_Coordinates(char station[]){
process_locator(station);
Station_Latitude = Latitude;
Station_Longitude = Longitude;
}
float Target_Distance(char target[]) {
float targetDistance;
process_locator(target);
Target_Latitude = Latitude;
Target_Longitude = Longitude;
targetDistance = (float) distance((double)Station_Latitude,(double)Station_Longitude,
(double)Target_Latitude,(double)Target_Longitude);
return targetDistance;
}
void process_locator(char locator[]) {
uint8_t A1, A2, N1, N2;
uint8_t A1_value, A2_value, N1_value, N2_value;
float Latitude_1, Latitude_2, Latitude_3;
float Longitude_1, Longitude_2, Longitude_3;
A1 = locator[0];
A2 = locator[1];
N1 = locator[2];
N2= locator [3];
A1_value = A1-65;
A2_value = A2-65;
N1_value = N1- 48;
N2_value = N2 - 48;
Latitude_1 = (float) A2_value * 10;
Latitude_2 = (float) N2_value;
Latitude_3 = (11.0/24.0 + 1.0/48.0) - 90.0;
Latitude = Latitude_1 + Latitude_2 + Latitude_3;
Longitude_1 = (float)A1_value * 20.0;
Longitude_2 = (float)N1_value * 2.0;
Longitude_3 = 11.0/12.0 + 1.0/24.0;
Longitude = Longitude_1 + Longitude_2 + Longitude_3 - 180.0;
}
// distance (km) on earth's surface from point 1 to point 2
double distance(double lat1, double lon1, double lat2, double lon2) {
double lat1r = deg2rad(lat1);
double lon1r = deg2rad(lon1);
double lat2r = deg2rad(lat2);
double lon2r = deg2rad(lon2);
return acos(sin(lat1r) * sin(lat2r)+cos(lat1r) * cos(lat2r) * cos(lon2r-lon1r)) * EARTH_RAD;
}
// convert degrees to radians
double deg2rad(double deg)
{
return deg * (PI / 180.0);
}

@ -0,0 +1,78 @@
//#include "maidenhead.h"
//#include <math.h>
//#include <stdio.h>
//#include <string.h>
//#ifdef __cplusplus
//extern "C" {
//#endif
// TODO This looks like a float change?? RSL
char letterizeR(int x) {
return (char) x + 65;
}
char* get_mh(double lat, double lon, int size) {
static char locator[11];
double LON_F[]={20,2.0,0.083333,0.008333,0.0003472083333333333};
double LAT_F[]={10,1.0,0.0416665,0.004166,0.0001735833333333333};
int i;
lon += 180;
lat += 90;
if (size <= 0 || size > 10) size = 6;
size/=2; size*=2;
for (i = 0; i < size/2; i++){
if (i % 2 == 1) {
locator[i*2] = (char) (lon/LON_F[i] + '0');
locator[i*2+1] = (char) (lat/LAT_F[i] + '0');
} else {
locator[i*2] = letterizeR((int) (lon/LON_F[i]));
locator[i*2+1] = letterizeR((int) (lat/LAT_F[i]));
}
lon = fmod(lon, LON_F[i]);
lat = fmod(lat, LAT_F[i]);
}
locator[i*2]=0;
return locator;
}
char* complete_mh(char* locator) {
static char locator2[11] = "LL55LL55LL";
int len = strlen(locator);
if (len >= 10) return locator;
memcpy(locator2, locator, strlen(locator));
return locator2;
}
double mh2lon(char* locator) {
double field, square, subsquare, extsquare, precsquare;
int len = strlen(locator);
if (len > 10) return 0;
if (len < 10) locator = complete_mh(locator);
field = (locator[0] - 'A') * 20.0;
square = (locator[2] - '0') * 2.0;
subsquare = (locator[4] - 'A') / 12.0;
extsquare = (locator[6] - '0') / 120.0;
precsquare = (locator[8] - 'A') / 2880.0;
return field + square + subsquare + extsquare + precsquare - 180;
}
double mh2lat(char* locator) {
double field, square, subsquare, extsquare, precsquare;
int len = strlen(locator);
if (len > 10) return 0;
if (len < 10) locator = complete_mh(locator);
field = (locator[1] - 'A') * 10.0;
square = (locator[3] - '0') * 1.0;
subsquare = (locator[5] - 'A') / 24.0;
extsquare = (locator[7] - '0') / 240.0;
precsquare = (locator[9] - 'A') / 5760.0;
return field + square + subsquare + extsquare + precsquare - 90;
}
//#ifdef __cplusplus
//}
//#endif

@ -0,0 +1,206 @@
// #include "text.h"
#include <string.h>
//extern bool true;
//extern bool false;
const char * trim_front(const char *str) {
// Skip leading whitespace
while (*str == ' ') {
str++;
}
return str;
}
void trim_back(char *str) {
// Skip trailing whitespace by replacing it with '\0' characters
int idx = strlen(str) - 1;
while (idx >= 0 && str[idx] == ' ') {
str[idx--] = '\0';
}
}
// 1) trims a string from the back by changing whitespaces to '\0'
// 2) trims a string from the front by skipping whitespaces
char * trim(char *str) {
str = (char *)trim_front(str);
trim_back(str);
// return a pointer to the first non-whitespace character
return str;
}
char to_upper(char c) {
return (c >= 'a' && c <= 'z') ? (c - 'a' + 'A') : c;
}
bool is_digit(char c) {
return (c >= '0') && (c <= '9');
}
bool is_letter(char c) {
return ((c >= 'A') && (c <= 'Z')) || ((c >= 'a') && (c <= 'z'));
}
bool is_space(char c) {
return (c == ' ');
}
bool in_range(char c, char min, char max) {
return (c >= min) && (c <= max);
}
bool starts_with(const char *string, const char *prefix) {
return 0 == memcmp(string, prefix, strlen(prefix));
}
bool equals(const char *string1, const char *string2) {
return 0 == strcmp(string1, string2);
}
int char_index(const char *string, char c) {
for (int i = 0; *string; ++i, ++string) {
if (c == *string) {
return i;
}
}
return -1; // Not found
}
// Text message formatting:
// - replaces lowercase letters with uppercase
// - merges consecutive spaces into single space
void fmtmsg(char *msg_out, const char *msg_in) {
char c;
char last_out = 0;
while ( (c = *msg_in) ) {
if (c != ' ' || last_out != ' ') {
last_out = to_upper(c);
*msg_out = last_out;
++msg_out;
}
++msg_in;
}
*msg_out = 0; // Add zero termination
}
// Parse a 2 digit integer from string
int dd_to_int(const char *str, int length) {
int result = 0;
bool negative;
int i;
if (str[0] == '-') {
negative = true;
i = 1; // Consume the - sign
}
else {
negative = false;
i = (str[0] == '+') ? 1 : 0; // Consume a + sign if found
}
while (i < length) {
if (str[i] == 0) break;
if (!is_digit(str[i])) break;
result *= 10;
result += (str[i] - '0');
++i;
}
return negative ? -result : result;
}
// Convert a 2 digit integer to string
void int_to_dd(char *str, int value, int width, bool full_sign) {
if (value < 0) {
*str = '-';
++str;
value = -value;
}
else if (full_sign) {
*str = '+';
++str;
}
int divisor = 1;
for (int i = 0; i < width - 1; ++i) {
divisor *= 10;
}
while (divisor >= 1) {
int digit = value / divisor;
*str = '0' + digit;
++str;
value -= digit * divisor;
divisor /= 10;
}
*str = 0; // Add zero terminator
}
// convert integer index to ASCII character according to one of 6 tables:
// table 0: " 0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ+-./?"
// table 1: " 0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ"
// table 2: "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ"
// table 3: "0123456789"
// table 4: " ABCDEFGHIJKLMNOPQRSTUVWXYZ"
// table 5: " 0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ/"
char charn(int c, int table_idx) {
if (table_idx != 2 && table_idx != 3) {
if (c == 0) return ' ';
c -= 1;
}
if (table_idx != 4) {
if (c < 10) return '0' + c;
c -= 10;
}
if (table_idx != 3) {
if (c < 26) return 'A' + c;
c -= 26;
}
if (table_idx == 0) {
if (c < 5) return "+-./?" [c];
}
else if (table_idx == 5) {
if (c == 0) return '/';
}
return '_'; // unknown character, should never get here
}
// Convert character to its index (charn in reverse) according to a table
int nchar(char c, int table_idx) {
int n = 0;
if (table_idx != 2 && table_idx != 3) {
if (c == ' ') return n + 0;
n += 1;
}
if (table_idx != 4) {
if (c >= '0' && c <= '9') return n + (c - '0');
n += 10;
}
if (table_idx != 3) {
if (c >= 'A' && c <= 'Z') return n + (c - 'A');
n += 26;
}
if (table_idx == 0) {
if (c == '+') return n + 0;
if (c == '-') return n + 1;
if (c == '.') return n + 2;
if (c == '/') return n + 3;
if (c == '?') return n + 4;
}
else if (table_idx == 5) {
if (c == '/') return n + 0;
}
// Character not found
return -1;
}

@ -0,0 +1,400 @@
/* unpackR.ino
* Basically the Goba unpack.h and .c with minor changes for Teensy
* Arduino use along with the floating point OpenAudio_ArduinoLibrary.
* Bob Larkin W7PUA, September 2022.
*
*/
/* Thank you to Kārlis Goba, YL3JG, https://github.com/kgoba/ft8_lib
* and to Charlie Hill, W5BAA, https://github.com/Rotron/Pocket-FT8
* as well as the all the contributors to the Joe Taylor WSJT project.
* See "The FT4 and FT8 Communication Protocols," Steve Franks, K9AN,
* Bill Somerville, G4WJS and Joe Taylor, K1JT, QEX July/August 2020
* pp 7-17 as well as https://www.physics.princeton.edu/pulsar/K1JT
*/
/* ***** MIT License ***
Copyright (c) 2018 Kārlis Goba
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.
*/
const uint32_t MAX22 = 4194304L;
const uint32_t NTOKENS = 2063592L;
const uint16_t MAXGRID4 = 32400L;
// n28 is a 28-bit integer, e.g. n28a or n28b, containing all the
// call sign bits from a packed message.
int unpack28(uint32_t n28, uint8_t ip, uint8_t i3, char *result) {
// Check for special tokens DE, QRZ, CQ, CQ_nnn, CQ_aaaa
if (n28 < NTOKENS) {
if (n28 <= 2) {
if (n28 == 0) strcpy(result, "DE");
if (n28 == 1) strcpy(result, "QRZ");
if (n28 == 2) strcpy(result, "CQ");
return 0; // Success
}
if (n28 <= 1002) {
// CQ_nnn with 3 digits
strcpy(result, "CQ ");
int_to_dd(result + 3, n28 - 3, 3, true);
return 0; // Success
}
if (n28 <= 532443L) {
// CQ_aaaa with 4 alphanumeric symbols
uint32_t n = n28 - 1003;
char aaaa[5];
aaaa[4] = '\0';
for (int i = 3; /* */; --i) {
aaaa[i] = charn(n % 27, 4);
if (i == 0) break;
n /= 27;
}
strcpy(result, "CQ ");
strcat(result, trim_front(aaaa));
return 0; // Success
}
// ? TODO: unspecified in the WSJT-X code
return -1;
}
n28 = n28 - NTOKENS;
if (n28 < MAX22) {
// This is a 22-bit hash of a result
//call hash22(n22,c13) !Retrieve result from hash table
// TODO: implement
// strcpy(result, "<...>");
result[0] = '<';
int_to_dd(result + 1, n28, 7, true);
result[8] = '>';
result[9] = '\0';
return 0;
}
// Standard callsign
uint32_t n = n28 - MAX22;
char callsign[7];
callsign[6] = '\0';
callsign[5] = charn(n % 27, 4);
n /= 27;
callsign[4] = charn(n % 27, 4);
n /= 27;
callsign[3] = charn(n % 27, 4);
n /= 27;
callsign[2] = charn(n % 10, 3);
n /= 10;
callsign[1] = charn(n % 36, 2);
n /= 36;
callsign[0] = charn(n % 37, 1);
// Skip trailing and leading whitespace in case of a short callsign
strcpy(result, trim(callsign));
if (strlen(result) == 0) return -1;
// Check if we should append /R or /P suffix
if (ip) {
if (i3 == 1) {
strcat(result, "/R");
}
else if (i3 == 2) {
strcat(result, "/P");
}
}
return 0; // Success
}
int unpack_type1(const uint8_t *a77, uint8_t i3, char *field1, char *field2, char *field3) {
uint32_t n28a, n28b;
uint16_t igrid4;
uint8_t ir;
// Extract packed fields
// read(c77,1000) n28a,ipa,n28b,ipb,ir,igrid4,i3
// 1000 format(2(b28,b1),b1,b15,b3)
n28a = (a77[0] << 21);
n28a |= (a77[1] << 13);
n28a |= (a77[2] << 5);
n28a |= (a77[3] >> 3);
n28b = ((a77[3] & 0x07) << 26);
n28b |= (a77[4] << 18);
n28b |= (a77[5] << 10);
n28b |= (a77[6] << 2);
n28b |= (a77[7] >> 6);
ir = ((a77[7] & 0x20) >> 5);
igrid4 = ((a77[7] & 0x1F) << 10);
igrid4 |= (a77[8] << 2);
igrid4 |= (a77[9] >> 6);
// Unpack both callsigns
if (unpack28(n28a >> 1, n28a & 0x01, i3, field1) < 0) {
return -1;
}
if (unpack28(n28b >> 1, n28b & 0x01, i3, field2) < 0) {
return -2;
}
// Fix "CQ_" to "CQ " -> already done in unpack28()
// TODO: add to recent calls
// if (field1[0] != '<' && strlen(field1) >= 4) {
// save_hash_call(field1)
// }
// if (field2[0] != '<' && strlen(field2) >= 4) {
// save_hash_call(field2)
// }
if (igrid4 <= MAXGRID4) {
// Extract 4 symbol grid locator
char *dst = field3;
uint16_t n = igrid4;
if (ir > 0) {
// In case of ir=1 add an "R" before grid
dst = stpcpy(dst, "R ");
}
dst[4] = '\0';
dst[3] = '0' + (n % 10);
n /= 10;
dst[2] = '0' + (n % 10);
n /= 10;
dst[1] = 'A' + (n % 18);
n /= 18;
dst[0] = 'A' + (n % 18);
// if(msg(1:3).eq.'CQ ' .and. ir.eq.1) unpk77_success=.false.
// if (ir > 0 && strncmp(field1, "CQ", 2) == 0) return -1;
}
else {
// Extract report
int irpt = igrid4 - MAXGRID4;
// Check special cases first
if (irpt == 1) field3[0] = '\0';
else if (irpt == 2) strcpy(field3, "RRR");
else if (irpt == 3) strcpy(field3, "RR73");
else if (irpt == 4) strcpy(field3, "73");
else if (irpt >= 5) {
char *dst = field3;
// Extract signal report as a two digit number with a + or - sign
if (ir > 0) {
*dst++ = 'R'; // Add "R" before report
}
int_to_dd(dst, irpt - 35, 2, true);
}
// if(msg(1:3).eq.'CQ ' .and. irpt.ge.2) unpk77_success=.false.
// if (irpt >= 2 && strncmp(field1, "CQ", 2) == 0) return -1;
}
return 0; // Success
}
int unpack_text(const uint8_t *a71, char *text) {
// TODO: test
uint8_t b71[9];
uint8_t carry = 0;
for (int i = 0; i < 9; ++i) {
b71[i] = carry | (a71[i] >> 1);
carry = (a71[i] & 1) ? 0x80 : 0;
}
char c14[14];
c14[13] = 0;
for (int idx = 12; idx >= 0; --idx) {
// Divide the long integer in b71 by 42
uint16_t rem = 0;
for (int i = 0; i < 9; ++i) {
rem = (rem << 8) | b71[i];
b71[i] = rem / 42;
rem = rem % 42;
}
c14[idx] = charn(rem, 0);
}
strcpy(text, trim(c14));
return 0; // Success
}
int unpack_telemetry(const uint8_t *a71, char *telemetry) {
uint8_t b71[9];
// Shift bits in a71 right by 1
uint8_t carry = 0;
for (int i = 0; i < 9; ++i) {
b71[i] = (carry << 7) | (a71[i] >> 1);
carry = (a71[i] & 0x01);
}
// Convert b71 to hexadecimal string
for (int i = 0; i < 9; ++i) {
uint8_t nibble1 = (b71[i] >> 4);
uint8_t nibble2 = (b71[i] & 0x0F);
char c1 = (nibble1 > 9) ? (nibble1 - 10 + 'A') : nibble1 + '0';
char c2 = (nibble2 > 9) ? (nibble2 - 10 + 'A') : nibble2 + '0';
telemetry[i * 2] = c1;
telemetry[i * 2 + 1] = c2;
}
telemetry[18] = '\0';
return 0;
}
//none standard for wsjt-x 2.0
//by KD8CEC
int unpack_nonstandard(const uint8_t *a77, char *field1, char *field2, char *field3)
{
/*
wsjt-x 2.1.0 rc5
read(c77,1050) n12,n58,iflip,nrpt,icq
1050 format(b12,b58,b1,b2,b1)
*/
uint32_t n12, iflip, nrpt, icq;
uint64_t n58;
n12 = (a77[0] << 4); //11 ~4 : 8
n12 |= (a77[1] >> 4); //3~0 : 12
n58 = ((uint64_t)(a77[1] & 0x0F) << 54); //57 ~ 54 : 4
n58 |= ((uint64_t)a77[2] << 46); //53 ~ 46 : 12
n58 |= ((uint64_t)a77[3] << 38); //45 ~ 38 : 12
n58 |= ((uint64_t)a77[4] << 30); //37 ~ 30 : 12
n58 |= ((uint64_t)a77[5] << 22); //29 ~ 22 : 12
n58 |= ((uint64_t)a77[6] << 14); //21 ~ 14 : 12
n58 |= ((uint64_t)a77[7] << 6); //13 ~ 6 : 12
n58 |= ((uint64_t)a77[8] >> 2); //5 ~ 0 : 765432 10
iflip = (a77[8] >> 1) & 0x01; //76543210
nrpt = ((a77[8] & 0x01) << 1);
nrpt |= (a77[9] >> 7); //76543210
icq = ((a77[9] >> 6) & 0x01);
char c11[12];
c11[11] = '\0';
for (int i = 10; /* no condition */ ; --i) {
c11[i] = charn(n58 % 38, 5);
if (i == 0) break;
n58 /= 38;
}
char call_3[15];
// should replace with hash12(n12, call_3);
// strcpy(call_3, "<...>");
call_3[0] = '<';
int_to_dd(call_3 + 1, n12, 4, true);
call_3[5] = '>';
call_3[6] = '\0';
char * call_1 = (iflip) ? c11 : call_3;
char * call_2 = (iflip) ? call_3 : c11;
//save_hash_call(c11_trimmed);
if (icq == 0) {
strcpy(field1, trim(call_1));
if (nrpt == 1)
strcpy(field3, "RRR");
else if (nrpt == 2)
strcpy(field3, "RR73");
else if (nrpt == 3)
strcpy(field3, "73");
else {
field3[0] = '\0';
}
} else {
strcpy(field1, "CQ");
field3[0] = '\0';
}
strcpy(field2, trim(call_2));
return 0;
}
int unpack77_fields(const uint8_t *a77, char *field1, char *field2, char *field3) {
uint8_t n3, i3;
// Extract n3 (bits 71..73) and i3 (bits 74..76)
n3 = ((a77[8] << 2) & 0x04) | ((a77[9] >> 6) & 0x03);
i3 = (a77[9] >> 3) & 0x07;
field1[0] = field2[0] = field3[0] = '\0';
if (i3 == 0 && n3 == 0) {
// 0.0 Free text
return unpack_text(a77, field1);
}
// else if (i3 == 0 && n3 == 1) {
// // 0.1 K1ABC RR73; W9XYZ <KH1/KH7Z> -11 28 28 10 5 71 DXpedition Mode
// }
// else if (i3 == 0 && n3 == 2) {
// // 0.2 PA3XYZ/P R 590003 IO91NP 28 1 1 3 12 25 70 EU VHF contest
// }
// else if (i3 == 0 && (n3 == 3 || n3 == 4)) {
// // 0.3 WA9XYZ KA1ABC R 16A EMA 28 28 1 4 3 7 71 ARRL Field Day
// // 0.4 WA9XYZ KA1ABC R 32A EMA 28 28 1 4 3 7 71 ARRL Field Day
// }
else if (i3 == 0 && n3 == 5) {
// 0.5 0123456789abcdef01 71 71 Telemetry (18 hex)
return unpack_telemetry(a77, field1);
}
else if (i3 == 1 || i3 == 2) {
// Type 1 (standard message) or Type 2 ("/P" form for EU VHF contest)
return unpack_type1(a77, i3, field1, field2, field3);
}
// else if (i3 == 3) {
// // Type 3: ARRL RTTY Contest
// }
else if (i3 == 4) {
// // Type 4: Nonstandard calls, e.g. <WA9XYZ> PJ4/KA1ABC RR73
// // One hashed call or "CQ"; one compound or nonstandard call with up
// // to 11 characters; and (if not "CQ") an optional RRR, RR73, or 73.
return unpack_nonstandard(a77, field1, field2, field3);
}
// else if (i3 == 5) {
// // Type 5: TU; W9XYZ K1ABC R-09 FN 1 28 28 1 7 9 74 WWROF contest
// }
// unknown type, should never get here
return -1;
}
int unpack77(const uint8_t *a77, char *message) {
char field1[14];
char field2[14];
char field3[7];
int rc = unpack77_fields(a77, field1, field2, field3);
if (rc < 0) return rc;
char *dst = message;
// int msg_sz = strlen(field1) + strlen(field2) + strlen(field3) + 2;
dst = stpcpy(dst, field1);
*dst++ = ' ';
dst = stpcpy(dst, field2);
*dst++ = ' ';
dst = stpcpy(dst, field3);
*dst = '\0';
return 0;
}

@ -6,6 +6,10 @@
* OpenAudio_TeensyLibrary.
* See radioFT8Modulator_F32 for information on the implementation.
* This INO is in the public domain.
*
* Rev 3 Oct 2022 Start up in msg 0, s/n = 0.0 dB. Allowed changes to
* initial SNR RSL
* Rev 10 Oct 2022 Added LED pulse every 15 sec. RSL
*/
#include "Arduino.h"
@ -32,6 +36,10 @@ AudioConnection_F32 patchCord4(filterFIRgeneral1, 0, audioOutI2S1, 1);
AudioConnection_F32 patchCord6(filterFIRgeneral1, rms1);
AudioControlSGTL5000 sgtl5000_1; //xy=357,318
// NOTE - This FIR filter has more taps than needed for a generator. The goal for
// this test is to be able to directly measure the noise in a 2500 Hz
// bandwidth. This FIR does that.
//
/* FIR filter to measure noise power in a 2500 Hz BW
* Designed with http://t-filter.appspot.com
* Sampling frequency: 48000 Hz
@ -158,7 +166,8 @@ bool displayClock = false;
bool displayPower = false;
bool sendEvery15Sec = true;
bool doing15SecSend = false;
float32_t snrDB = 0.0f;
float32_t snrDB = 10.0f; // <-- Set initial SNR here
const int ledPin = 13; // Blink LED every 15 sec
void setup(void) {
Serial.begin(9600); delay(500);
@ -167,7 +176,7 @@ void setup(void) {
Serial.println("Use 0 to 7 to set message.");
AudioMemory_F32(20, audio_settings);
AudioMemory(30);
FT8Mod1.setSampleRate_Hz(48000.0f);
FT8Mod1.ft8Initialize();
FT8Mod1.frequency(700.0f);
@ -176,17 +185,19 @@ void setup(void) {
// 4.589 as a power ratio. The filter is very close to a 2500 Hz BW
// so this is close to the WSJT defined S/N. Show on WSJT-X as -1.8 dB S/N.
// (Power as used here means the RMS object output squared.)
FT8Mod1.amplitude(0.04668); // for 0 dB S/N.
FT8Mod1.amplitude(powf(10.0f, 0.05f*(snrDB-26.617)));
filterFIRgeneral1.LoadCoeffs(597, filter2500BP, pStateArray);
GaussianWhiteNoise1.amplitude(0.1f); // Do not change unless breaking the cal is wanted.
GaussianWhiteNoise1.amplitude(0.1f); // Do not change from 0.1f unless breaking the cal is wanted.
sgtl5000_1.enable();
delay(5);
t60 = 0.000f;
t60 = 0.000f; // Reset clock
t60Last = t60;
t60Base = millis();
sendNext = 0; // Rev 3 Oct 2022
}
void loop() {
@ -372,6 +383,10 @@ void loop() {
FT8Mod1.sendData((char*) inputString[sendNext], 1, 0, 0);
Serial.println("Send every 15 sec");
doing15SecSend = true;
digitalWrite(ledPin, HIGH); // set the LED on
delay(100);
digitalWrite(ledPin, LOW); // set the LED on
}
} // End. loop

@ -0,0 +1,347 @@
/*
* New FT8Transmit7.ino Bob Larkin 23 Oct 2022
*
* Generates 7 FT8 signals along with added white Gaussian noise.
* S/N is controlled accurately. Uses Teensy Floating Point
* OpenAudio_TeensyLibrary. S/N is set according to frequency:
* 700 -22 dB
* 850 -21 dB
* 1000 -20 dB
* 1150 -19 dB
* 1300 -18 dB
* 1450 -17 dB
* 1600 -16 dB
* The S/N is also indicated in the signal-report field.
* All seven signals are generated every 15 seconds.
*
* Time zeroing can be done by a USB-serial command =<CR>
* or even easier is to just apply power 2-seconds before any 15 second
* PC reading. The LED on the Teensy 4.x blinks at the start of
* each 15 second period. All 15 second periods are used for transmit
* from this test generator.
*
* Required hardware is a Teensy 4.0 (or 4.1) along with the 4.x audio
* adapter. Output on the adapter board is either the left or right channel.
* Once programmed, a PC is no longer needed to run the Teensy. See
* https://www.pjrc.com/store/teensy40.html for board info and ordering.
*
* This INO is an example in the Teensy Floating Point (F32) library,
* https://github.com/chipaudette/OpenAudio_ArduinoLibrary. That library,
* along with the Arduino IDE and the Teensyduino additions are
* needed to compile and link this INO.
*
* See radioFT8Modulator_F32 for information on the implementation.
* This INO is in the public domain.
*
*/
#include "Arduino.h"
#include "OpenAudio_ArduinoLibrary.h"
#include "AudioStream_F32.h"
#include <Audio.h>
// Only 48 and 96 kHz audio sample rates are currently supported.
const float sample_rate_Hz = 48000.0f;
const int audio_block_samples = 128;
AudioSettings_F32 audio_settings(sample_rate_Hz, audio_block_samples);
AudioSynthGaussian_F32 GaussianWhiteNoise1(audio_settings);
RadioFT8Modulator_F32 FT8Mod1;
RadioFT8Modulator_F32 FT8Mod2;
RadioFT8Modulator_F32 FT8Mod3;
RadioFT8Modulator_F32 FT8Mod4;
RadioFT8Modulator_F32 FT8Mod5;
RadioFT8Modulator_F32 FT8Mod6;
RadioFT8Modulator_F32 FT8Mod7;
AudioMixer8_F32 mixer8_1;
AudioFilterFIRGeneral_F32 filterFIRgeneral1(audio_settings);
AudioOutputI2S_F32 audioOutI2S1(audio_settings);
AudioConnection_F32 patchCord1(GaussianWhiteNoise1, 0, mixer8_1, 0);
AudioConnection_F32 patchCord2(FT8Mod1, 0, mixer8_1, 1);
AudioConnection_F32 patchCord3(FT8Mod2, 0, mixer8_1, 2);
AudioConnection_F32 patchCord4(FT8Mod3, 0, mixer8_1, 3);
AudioConnection_F32 patchCord5(FT8Mod4, 0, mixer8_1, 4);
AudioConnection_F32 patchCord6(FT8Mod5, 0, mixer8_1, 5);
AudioConnection_F32 patchCord7(FT8Mod6, 0, mixer8_1, 6);
AudioConnection_F32 patchCord8(FT8Mod7, 0, mixer8_1, 7);
AudioConnection_F32 patchCord9(mixer8_1, filterFIRgeneral1);
AudioConnection_F32 patchCordA(filterFIRgeneral1, 0, audioOutI2S1, 0);
AudioConnection_F32 patchCordB(filterFIRgeneral1, 0, audioOutI2S1, 1);
AudioControlSGTL5000 sgtl5000_1; //xy=357,318
// NOTE - This FIR filter has more taps than needed for a generator. The goal for
// this test is to be able to directly measure the noise in a 2500 Hz
// bandwidth. This FIR does that.
//
/* FIR filter to measure noise power in a 2500 Hz BW
* Designed with http://t-filter.appspot.com
* Sampling frequency: 48000 Hz
* 0 Hz to 100 Hz and 3000 Hz to 24000 Hz Attenuation = 60.031 dB
* 330 Hz to 2770 Hz Ripple = 0.073 dB
*/
static float32_t filter2500BP[597] = {
-0.0005125820f,-0.0000202947f, 0.0000003593f, 0.0000329934f, 0.0000736751f, 0.0001169578f,
0.0001564562f, 0.0001855962f, 0.0001984728f, 0.0001906737f, 0.0001599822f, 0.0001068279f,
0.0000344273f,-0.0000514436f,-0.0001430419f,-0.0002315220f,-0.0003080131f,-0.0003647587f,
-0.0003961436f,-0.0003995218f,-0.0003756478f,-0.0003287024f,-0.0002658396f,-0.0001963221f,
-0.0001303695f,-0.0000777464f,-0.0000465332f,-0.0000418429f,-0.0000651581f,-0.0001139975f,
-0.0001821358f,-0.0002604090f,-0.0003379262f,-0.0004035583f,-0.0004475075f,-0.0004627523f,
-0.0004461496f,-0.0003990178f,-0.0003271062f,-0.0002399160f,-0.0001495029f,-0.0000688527f,
-0.0000100068f, 0.0000176282f, 0.0000087805f,-0.0000368277f,-0.0001142343f,-0.0002137524f,
-0.0003221742f,-0.0004245023f,-0.0005060412f,-0.0005544731f,-0.0005617283f,-0.0005252710f,
-0.0004486501f,-0.0003412138f,-0.0002169625f,-0.0000927250f, 0.0000141208f, 0.0000880971f,
0.0001179086f, 0.0000982361f, 0.0000307076f,-0.0000761311f,-0.0002078708f,-0.0003460213f,
-0.0004701224f,-0.0005615004f,-0.0006049803f,-0.0005918278f,-0.0005209351f,-0.0003992998f,
-0.0002412975f,-0.0000668730f, 0.0001011003f, 0.0002399869f, 0.0003306072f, 0.0003600909f,
0.0003239133f, 0.0002268029f, 0.0000823809f,-0.0000884979f,-0.0002604794f,-0.0004071616f,
-0.0005048299f,-0.0005359033f,-0.0004916409f,-0.0003736551f,-0.0001940102f, 0.0000261329f,
0.0002593430f, 0.0004753909f, 0.0006458134f, 0.0007476677f, 0.0007671322f, 0.0007017674f,
0.0005611468f, 0.0003658605f, 0.0001449418f,-0.0000679871f,-0.0002393698f,-0.0003405009f,
-0.0003517550f,-0.0002656412f,-0.0000882146f, 0.0001613566f, 0.0004531208f, 0.0007502948f,
0.0010142494f, 0.0012099822f, 0.0013111621f, 0.0013041379f, 0.0011902347f, 0.0009859932f,
0.0007212731f, 0.0004353657f, 0.0001717278f,-0.0000281207f,-0.0001305200f,-0.0001146943f,
0.0000239082f, 0.0002725259f, 0.0006024022f, 0.0009724061f, 0.0013345069f, 0.0016403901f,
0.0018483209f, 0.0019292574f, 0.0018713163f, 0.0016819017f, 0.0013872308f, 0.0010291844f,
0.0006595979f, 0.0003334254f, 0.0001008215f,-0.0000000058f, 0.0000514030f, 0.0002543686f,
0.0005865884f, 0.0010066897f, 0.0014595849f, 0.0018838923f, 0.0022204845f, 0.0024209305f,
0.0024546503f, 0.0023137474f, 0.0020147314f, 0.0015968377f, 0.0011170820f, 0.0006426406f,
0.0002415985f,-0.0000267023f,-0.0001203145f,-0.0000211214f, 0.0002619020f, 0.0006935370f,
0.0012155342f, 0.0017563231f, 0.0022384277f, 0.0025907218f, 0.0027584970f, 0.0027114957f,
0.0024488224f, 0.0019998882f, 0.0014211081f, 0.0007886354f, 0.0001880784f,-0.0002974170f,
-0.0005990413f,-0.0006724584f,-0.0005047619f,-0.0001171406f, 0.0004372104f, 0.0010797374f,
0.0017169949f, 0.0022534601f, 0.0026050371f, 0.0027112878f, 0.0025446519f, 0.0021152693f,
0.0014705327f, 0.0006894468f,-0.0001277897f,-0.0008733366f,-0.0014468246f,-0.0017698095f,
-0.0017974750f,-0.0015259241f,-0.0009938711f,-0.0002783418f, 0.0005151815f, 0.0012669280f,
0.0018594224f, 0.0021942034f, 0.0022063046f, 0.0018744400f, 0.0012252608f, 0.0003308740f,
-0.0006999772f,-0.0017363651f,-0.0026430272f,-0.0032994372f,-0.0036172996f,-0.0035539945f,
-0.0031199655f,-0.0023787848f,-0.0014397352f,-0.0004436511f, 0.0004561031f, 0.0011150128f,
0.0014181900f, 0.0012975421f, 0.0007428372f,-0.0001950981f,-0.0014097317f,-0.0027521917f,
-0.0040510049f,-0.0051355902f,-0.0058603728f,-0.0061261746f,-0.0058958745f,-0.0052041918f,
-0.0041474660f,-0.0028816782f,-0.0015956931f,-0.0004880525f, 0.0002612250f, 0.0005167695f,
0.0002085432f,-0.0006559859f,-0.0019902208f,-0.0036379161f,-0.0053928385f,-0.0070261631f,
-0.0083180284f,-0.0090889780f,-0.0092268159f,-0.0087049647f,-0.0075894402f,-0.0060330006f,
-0.0042568860f,-0.0025221767f,-0.0010944561f,-0.0002064388f,-0.0000237284f,-0.0006187163f,
-0.0019563607f,-0.0038947756f,-0.0062005014f,-0.0085775775f,-0.0107065383f,-0.0122883661f,
-0.0130875874f,-0.0129684039f,-0.0119185125f,-0.0100567406f,-0.0076227165f,-0.0049491711f,
-0.0024198814f,-0.0004183923f, 0.0007258785f, 0.0007867696f,-0.0003212561f,-0.0025231429f,
-0.0055845169f,-0.0091349479f,-0.0127114002f,-0.0158169578f,-0.0179877599f,-0.0188595572f,
-0.0182248418f,-0.0160724049f,-0.0126028433f,-0.0082166040f,-0.0034743283f, 0.0009670264f,
0.0044354922f, 0.0063335060f, 0.0062244751f, 0.0039053136f,-0.0005450570f,-0.0067487839f,
-0.0140477185f,-0.0215575093f,-0.0282527468f,-0.0330748862f,-0.0350513372f,-0.0334119094f,
-0.0276905793f,-0.0177980957f,-0.0040578279f, 0.0128017918f, 0.0316985253f, 0.0512872217f,
0.0700815899f, 0.0865943871f, 0.0994813474f, 0.1076734313f, 0.1104831570f, 0.1076734313f,
0.0994813474f, 0.0865943871f, 0.0700815899f, 0.0512872217f, 0.0316985253f, 0.0128017918f,
-0.0040578279f,-0.0177980957f,-0.0276905793f,-0.0334119094f,-0.0350513372f,-0.0330748862f,
-0.0282527468f,-0.0215575093f,-0.0140477185f,-0.0067487839f,-0.0005450570f, 0.0039053136f,
0.0062244751f, 0.0063335060f, 0.0044354922f, 0.0009670264f,-0.0034743283f,-0.0082166040f,
-0.0126028433f,-0.0160724049f,-0.0182248418f,-0.0188595572f,-0.0179877599f,-0.0158169578f,
-0.0127114002f,-0.0091349479f,-0.0055845169f,-0.0025231429f,-0.0003212561f, 0.0007867696f,
0.0007258785f,-0.0004183923f,-0.0024198814f,-0.0049491711f,-0.0076227165f,-0.0100567406f,
-0.0119185125f,-0.0129684039f,-0.0130875874f,-0.0122883661f,-0.0107065383f,-0.0085775775f,
-0.0062005014f,-0.0038947756f,-0.0019563607f,-0.0006187163f,-0.0000237284f,-0.0002064388f,
-0.0010944561f,-0.0025221767f,-0.0042568860f,-0.0060330006f,-0.0075894402f,-0.0087049647f,
-0.0092268159f,-0.0090889780f,-0.0083180284f,-0.0070261631f,-0.0053928385f,-0.0036379161f,
-0.0019902208f,-0.0006559859f, 0.0002085432f, 0.0005167695f, 0.0002612250f,-0.0004880525f,
-0.0015956931f,-0.0028816782f,-0.0041474660f,-0.0052041918f,-0.0058958745f,-0.0061261746f,
-0.0058603728f,-0.0051355902f,-0.0040510049f,-0.0027521917f,-0.0014097317f,-0.0001950981f,
0.0007428372f, 0.0012975421f, 0.0014181900f, 0.0011150128f, 0.0004561031f,-0.0004436511f,
-0.0014397352f,-0.0023787848f,-0.0031199655f,-0.0035539945f,-0.0036172996f,-0.0032994372f,
-0.0026430272f,-0.0017363651f,-0.0006999772f, 0.0003308740f, 0.0012252608f, 0.0018744400f,
0.0022063046f, 0.0021942034f, 0.0018594224f, 0.0012669280f, 0.0005151815f,-0.0002783418f,
-0.0009938711f,-0.0015259241f,-0.0017974750f,-0.0017698095f,-0.0014468246f,-0.0008733366f,
-0.0001277897f, 0.0006894468f, 0.0014705327f, 0.0021152693f, 0.0025446519f, 0.0027112878f,
0.0026050371f, 0.0022534601f, 0.0017169949f, 0.0010797374f, 0.0004372104f,-0.0001171406f,
-0.0005047619f,-0.0006724584f,-0.0005990413f,-0.0002974170f, 0.0001880784f, 0.0007886354f,
0.0014211081f, 0.0019998882f, 0.0024488224f, 0.0027114957f, 0.0027584970f, 0.0025907218f,
0.0022384277f, 0.0017563231f, 0.0012155342f, 0.0006935370f, 0.0002619020f,-0.0000211214f,
-0.0001203145f,-0.0000267023f, 0.0002415985f, 0.0006426406f, 0.0011170820f, 0.0015968377f,
0.0020147314f, 0.0023137474f, 0.0024546503f, 0.0024209305f, 0.0022204845f, 0.0018838923f,
0.0014595849f, 0.0010066897f, 0.0005865884f, 0.0002543686f, 0.0000514030f,-0.0000000058f,
0.0001008215f, 0.0003334254f, 0.0006595979f, 0.0010291844f, 0.0013872308f, 0.0016819017f,
0.0018713163f, 0.0019292574f, 0.0018483209f, 0.0016403901f, 0.0013345069f, 0.0009724061f,
0.0006024022f, 0.0002725259f, 0.0000239082f,-0.0001146943f,-0.0001305200f,-0.0000281207f,
0.0001717278f, 0.0004353657f, 0.0007212731f, 0.0009859932f, 0.0011902347f, 0.0013041379f,
0.0013111621f, 0.0012099822f, 0.0010142494f, 0.0007502948f, 0.0004531208f, 0.0001613566f,
-0.0000882146f,-0.0002656412f,-0.0003517550f,-0.0003405009f,-0.0002393698f,-0.0000679871f,
0.0001449418f, 0.0003658605f, 0.0005611468f, 0.0007017674f, 0.0007671322f, 0.0007476677f,
0.0006458134f, 0.0004753909f, 0.0002593430f, 0.0000261329f,-0.0001940102f,-0.0003736551f,
-0.0004916409f,-0.0005359033f,-0.0005048299f,-0.0004071616f,-0.0002604794f,-0.0000884979f,
0.0000823809f, 0.0002268029f, 0.0003239133f, 0.0003600909f, 0.0003306072f, 0.0002399869f,
0.0001011003f,-0.0000668730f,-0.0002412975f,-0.0003992998f,-0.0005209351f,-0.0005918278f,
-0.0006049803f,-0.0005615004f,-0.0004701224f,-0.0003460213f,-0.0002078708f,-0.0000761311f,
0.0000307076f, 0.0000982361f, 0.0001179086f, 0.0000880971f, 0.0000141208f,-0.0000927250f,
-0.0002169625f,-0.0003412138f,-0.0004486501f,-0.0005252710f,-0.0005617283f,-0.0005544731f,
-0.0005060412f,-0.0004245023f,-0.0003221742f,-0.0002137524f,-0.0001142343f,-0.0000368277f,
0.0000087805f, 0.0000176282f,-0.0000100068f,-0.0000688527f,-0.0001495029f,-0.0002399160f,
-0.0003271062f,-0.0003990178f,-0.0004461496f,-0.0004627523f,-0.0004475075f,-0.0004035583f,
-0.0003379262f,-0.0002604090f,-0.0001821358f,-0.0001139975f,-0.0000651581f,-0.0000418429f,
-0.0000465332f,-0.0000777464f,-0.0001303695f,-0.0001963221f,-0.0002658396f,-0.0003287024f,
-0.0003756478f,-0.0003995218f,-0.0003961436f,-0.0003647587f,-0.0003080131f,-0.0002315220f,
-0.0001430419f,-0.0000514436f, 0.0000344273f, 0.0001068279f, 0.0001599822f, 0.0001906737f,
0.0001984728f, 0.0001855962f, 0.0001564562f, 0.0001169578f, 0.0000736751f, 0.0000329934f,
0.0000003593f,-0.0000202947f,-0.0005125820f};
// Messages 0 to 7, 0 is not used
const char* inputString[] = {
"ABCDEFG123456",
"A1AA B1BB -22",
"A1AA B1BB -21",
"A1AA B1BB -20",
"A1AA B1BB -19",
"A1AA B1BB -18",
"A1AA B1BB -17",
"A1AA B1BB -16"};
float32_t pStateArray[1322]; // 2*597+128 for FIR filter
const int ledPin = 13; // Blink LED every 15 sec
uint32_t tMillis;
uint32_t tMillisOffset = 0UL;
void setup(void) {
Serial.begin(9600); delay(500);
Serial.println("FT8Transmit7.ino Ver 0.1 23 Oct 2022 W7PUA");
Serial.println("Use '=' to zero FT8 clock.");
AudioMemory_F32(20, audio_settings);
AudioMemory(30);
FT8Mod1.setSampleRate_Hz(48000.0f);
FT8Mod1.ft8Initialize();
FT8Mod1.frequency(700.0f);
// Calibration note: For the following = 0.1 and the GWN amplitude at 0.1,
// the power S/N at the output of the FIR filter is 6.617 dB or
// 4.589 as a power ratio. The filter is very close to a 2500 Hz BW
// so this is close to the WSJT defined S/N. Show on WSJT-X as -1.8 dB S/N.
// (Power as used here means the RMS object output squared.)
FT8Mod1.amplitude(powf(10.0f, 0.05f*(-22-26.617))); // snr = -22 dB
FT8Mod2.setSampleRate_Hz(48000.0f);
FT8Mod2.ft8Initialize();
FT8Mod2.frequency(850.0f);
FT8Mod2.amplitude(powf(10.0f, 0.05f*(-21-26.617))); // snr = -21 dB
FT8Mod3.setSampleRate_Hz(48000.0f);
FT8Mod3.ft8Initialize();
FT8Mod3.frequency(1000.0f);
FT8Mod3.amplitude(powf(10.0f, 0.05f*(-20-26.617))); // snr = -20 dB
FT8Mod4.setSampleRate_Hz(48000.0f);
FT8Mod4.ft8Initialize();
FT8Mod4.frequency(1150.0f);
FT8Mod4.amplitude(powf(10.0f, 0.05f*(-19-26.617))); // snr = -19 dB
FT8Mod5.setSampleRate_Hz(48000.0f);
FT8Mod5.ft8Initialize();
FT8Mod5.frequency(1300.0f);
FT8Mod5.amplitude(powf(10.0f, 0.05f*(-18-26.617))); // snr = -18 dB
FT8Mod6.setSampleRate_Hz(48000.0f);
FT8Mod6.ft8Initialize();
FT8Mod6.frequency(1450.0f);
FT8Mod6.amplitude(powf(10.0f, 0.05f*(-17-26.617))); // snr = -17 dB
FT8Mod7.setSampleRate_Hz(48000.0f);
FT8Mod7.ft8Initialize();
FT8Mod7.frequency(1600.0f);
FT8Mod7.amplitude(powf(10.0f, 0.05f*(-16-26.617))); // snr = -16 dB
filterFIRgeneral1.LoadCoeffs(597, filter2500BP, pStateArray);
GaussianWhiteNoise1.amplitude(0.1f); // Do not change from 0.1f unless breaking the cal is wanted.
sgtl5000_1.enable();
delay(5);
// This is intended as running in the Teensy unattended.
// For this, the clock will just use the millisec() clock.
tMillis = millis();
}
void loop() {
int16_t inCmd;
if( Serial.available() )
{
inCmd = Serial.read();
if(inCmd=='=') //Set local clock to zero
{
tMillis = millis();
tMillisOffset = 0UL;
Serial.println("Clock Zero'd");
}
else if(inCmd=='p' || inCmd=='P') // Increase clock 0.1 sec
{
tMillisOffset += 100UL;
Serial.println("Increase clock 0.1 sec");
}
else if(inCmd=='l' || inCmd=='L') // Decrease clock 0.1 sec
{
tMillisOffset -= 100UL;
Serial.println("Decrease clock 0.1 sec");
}
else if(inCmd=='-') // Increase clock 1 sec
{
tMillisOffset += 1000UL;
Serial.println("Increase clock 1 sec");
}
else if(inCmd==',') // Decrease clock 1 sec
{
tMillisOffset -= 1000UL;
Serial.println("Decrease clock 1 sec");
}
else if(inCmd=='?')
{
Serial.println("= Set local FT-8 clock to 0");
Serial.println("p, P Increase local FT8 clock by 0.1 sec");
Serial.println("l, L Decrease local FT8 clock by 0.1 sec");
Serial.println("- Increase local FT8 clock by 1 sec");
Serial.println(", Decrease local FT8 clock by 1 sec");
Serial.println("? Help Display (this message)");
}
else if(inCmd>35) // Ignore anything below '#'
Serial.println("Cmd ???");
} // End, if Serial Available
// Send every 15 sec
if( !FT8Mod7.FT8TransmitBusy() && ((millis() + tMillisOffset) - tMillis ) >= 15000UL )
{
tMillis += 15000UL;
mixer8_1.gain(0, 1.0f); // Noise
mixer8_1.gain(1, 1.0f);
mixer8_1.gain(2, 1.0f);
mixer8_1.gain(3, 1.0f);
mixer8_1.gain(4, 1.0f);
mixer8_1.gain(5, 1.0f);
mixer8_1.gain(6, 1.0f);
mixer8_1.gain(7, 1.0f);
FT8Mod1.cancelTransmit();
FT8Mod1.sendData((char*) inputString[1], 1, 0, 0);
FT8Mod2.cancelTransmit();
FT8Mod2.sendData((char*) inputString[2], 1, 0, 0);
FT8Mod3.cancelTransmit();
FT8Mod3.sendData((char*) inputString[3], 1, 0, 0);
FT8Mod4.cancelTransmit();
FT8Mod4.sendData((char*) inputString[4], 1, 0, 0);
FT8Mod5.cancelTransmit();
FT8Mod5.sendData((char*) inputString[5], 1, 0, 0);
FT8Mod6.cancelTransmit();
FT8Mod6.sendData((char*) inputString[6], 1, 0, 0);
FT8Mod7.cancelTransmit();
FT8Mod7.sendData((char*) inputString[7], 1, 0, 0);
Serial.println("Send every 15 sec");
digitalWrite(ledPin, HIGH); // set the LED on
delay(100);
digitalWrite(ledPin, LOW); // set the LED on
}
// Turn off
if( !FT8Mod7.FT8TransmitBusy() && (millis() + tMillisOffset) - tMillis >= 13000UL )
{
// mixer8_1.gain(0, 0.0f); // Noise
mixer8_1.gain(1, 0.0f);
mixer8_1.gain(2, 0.0f);
mixer8_1.gain(3, 0.0f);
mixer8_1.gain(4, 0.0f);
mixer8_1.gain(5, 0.0f);
mixer8_1.gain(6, 0.0f);
mixer8_1.gain(7, 0.0f);
}
} // End. loop

@ -0,0 +1,348 @@
/*
* New FT8Transmit7HP.ino Bob Larkin 25 Oct 2022
* Same as FT8Transmit7.ino but higher power levels
*
* Generates 7 FT8 signals along with added white Gaussian noise.
* S/N is controlled accurately. Uses Teensy Floating Point
* OpenAudio_TeensyLibrary. S/N is set according to frequency:
* 700 -22 dB
* 850 -19 dB
* 1000 -16 dB
* 1150 -13 dB
* 1300 -10 dB
* 1450 -7 dB
* 1600 -4 dB
* The S/N is also indicated in the signal-report field.
* All seven signals are generated every 15 seconds.
*
* Time zeroing can be done by a USB-serial command =<CR>
* or even easier is to just apply power 2-seconds before any 15 second
* PC reading. The LED on the Teensy 4.x blinks at the start of
* each 15 second period. All 15 second periods are used for transmit
* from this test generator.
*
* Required hardware is a Teensy 4.0 (or 4.1) along with the 4.x audio
* adapter. Output on the adapter board is either the left or right channel.
* Once programmed, a PC is no longer needed to run the Teensy. See
* https://www.pjrc.com/store/teensy40.html for board info and ordering.
*
* This INO is an example in the Teensy Floating Point (F32) library,
* https://github.com/chipaudette/OpenAudio_ArduinoLibrary. That library,
* along with the Arduino IDE and the Teensyduino additions are
* needed to compile and link this INO.
*
* See radioFT8Modulator_F32 for information on the implementation.
* This INO is in the public domain.
*
*/
#include "Arduino.h"
#include "OpenAudio_ArduinoLibrary.h"
#include "AudioStream_F32.h"
#include <Audio.h>
// Only 48 and 96 kHz audio sample rates are currently supported.
const float sample_rate_Hz = 48000.0f;
const int audio_block_samples = 128;
AudioSettings_F32 audio_settings(sample_rate_Hz, audio_block_samples);
AudioSynthGaussian_F32 GaussianWhiteNoise1(audio_settings);
RadioFT8Modulator_F32 FT8Mod1;
RadioFT8Modulator_F32 FT8Mod2;
RadioFT8Modulator_F32 FT8Mod3;
RadioFT8Modulator_F32 FT8Mod4;
RadioFT8Modulator_F32 FT8Mod5;
RadioFT8Modulator_F32 FT8Mod6;
RadioFT8Modulator_F32 FT8Mod7;
AudioMixer8_F32 mixer8_1;
AudioFilterFIRGeneral_F32 filterFIRgeneral1(audio_settings);
AudioOutputI2S_F32 audioOutI2S1(audio_settings);
AudioConnection_F32 patchCord1(GaussianWhiteNoise1, 0, mixer8_1, 0);
AudioConnection_F32 patchCord2(FT8Mod1, 0, mixer8_1, 1);
AudioConnection_F32 patchCord3(FT8Mod2, 0, mixer8_1, 2);
AudioConnection_F32 patchCord4(FT8Mod3, 0, mixer8_1, 3);
AudioConnection_F32 patchCord5(FT8Mod4, 0, mixer8_1, 4);
AudioConnection_F32 patchCord6(FT8Mod5, 0, mixer8_1, 5);
AudioConnection_F32 patchCord7(FT8Mod6, 0, mixer8_1, 6);
AudioConnection_F32 patchCord8(FT8Mod7, 0, mixer8_1, 7);
AudioConnection_F32 patchCord9(mixer8_1, filterFIRgeneral1);
AudioConnection_F32 patchCordA(filterFIRgeneral1, 0, audioOutI2S1, 0);
AudioConnection_F32 patchCordB(filterFIRgeneral1, 0, audioOutI2S1, 1);
AudioControlSGTL5000 sgtl5000_1; //xy=357,318
// NOTE - This FIR filter has more taps than needed for a generator. The goal for
// this test is to be able to directly measure the noise in a 2500 Hz
// bandwidth. This FIR does that.
//
/* FIR filter to measure noise power in a 2500 Hz BW
* Designed with http://t-filter.appspot.com
* Sampling frequency: 48000 Hz
* 0 Hz to 100 Hz and 3000 Hz to 24000 Hz Attenuation = 60.031 dB
* 330 Hz to 2770 Hz Ripple = 0.073 dB
*/
static float32_t filter2500BP[597] = {
-0.0005125820f,-0.0000202947f, 0.0000003593f, 0.0000329934f, 0.0000736751f, 0.0001169578f,
0.0001564562f, 0.0001855962f, 0.0001984728f, 0.0001906737f, 0.0001599822f, 0.0001068279f,
0.0000344273f,-0.0000514436f,-0.0001430419f,-0.0002315220f,-0.0003080131f,-0.0003647587f,
-0.0003961436f,-0.0003995218f,-0.0003756478f,-0.0003287024f,-0.0002658396f,-0.0001963221f,
-0.0001303695f,-0.0000777464f,-0.0000465332f,-0.0000418429f,-0.0000651581f,-0.0001139975f,
-0.0001821358f,-0.0002604090f,-0.0003379262f,-0.0004035583f,-0.0004475075f,-0.0004627523f,
-0.0004461496f,-0.0003990178f,-0.0003271062f,-0.0002399160f,-0.0001495029f,-0.0000688527f,
-0.0000100068f, 0.0000176282f, 0.0000087805f,-0.0000368277f,-0.0001142343f,-0.0002137524f,
-0.0003221742f,-0.0004245023f,-0.0005060412f,-0.0005544731f,-0.0005617283f,-0.0005252710f,
-0.0004486501f,-0.0003412138f,-0.0002169625f,-0.0000927250f, 0.0000141208f, 0.0000880971f,
0.0001179086f, 0.0000982361f, 0.0000307076f,-0.0000761311f,-0.0002078708f,-0.0003460213f,
-0.0004701224f,-0.0005615004f,-0.0006049803f,-0.0005918278f,-0.0005209351f,-0.0003992998f,
-0.0002412975f,-0.0000668730f, 0.0001011003f, 0.0002399869f, 0.0003306072f, 0.0003600909f,
0.0003239133f, 0.0002268029f, 0.0000823809f,-0.0000884979f,-0.0002604794f,-0.0004071616f,
-0.0005048299f,-0.0005359033f,-0.0004916409f,-0.0003736551f,-0.0001940102f, 0.0000261329f,
0.0002593430f, 0.0004753909f, 0.0006458134f, 0.0007476677f, 0.0007671322f, 0.0007017674f,
0.0005611468f, 0.0003658605f, 0.0001449418f,-0.0000679871f,-0.0002393698f,-0.0003405009f,
-0.0003517550f,-0.0002656412f,-0.0000882146f, 0.0001613566f, 0.0004531208f, 0.0007502948f,
0.0010142494f, 0.0012099822f, 0.0013111621f, 0.0013041379f, 0.0011902347f, 0.0009859932f,
0.0007212731f, 0.0004353657f, 0.0001717278f,-0.0000281207f,-0.0001305200f,-0.0001146943f,
0.0000239082f, 0.0002725259f, 0.0006024022f, 0.0009724061f, 0.0013345069f, 0.0016403901f,
0.0018483209f, 0.0019292574f, 0.0018713163f, 0.0016819017f, 0.0013872308f, 0.0010291844f,
0.0006595979f, 0.0003334254f, 0.0001008215f,-0.0000000058f, 0.0000514030f, 0.0002543686f,
0.0005865884f, 0.0010066897f, 0.0014595849f, 0.0018838923f, 0.0022204845f, 0.0024209305f,
0.0024546503f, 0.0023137474f, 0.0020147314f, 0.0015968377f, 0.0011170820f, 0.0006426406f,
0.0002415985f,-0.0000267023f,-0.0001203145f,-0.0000211214f, 0.0002619020f, 0.0006935370f,
0.0012155342f, 0.0017563231f, 0.0022384277f, 0.0025907218f, 0.0027584970f, 0.0027114957f,
0.0024488224f, 0.0019998882f, 0.0014211081f, 0.0007886354f, 0.0001880784f,-0.0002974170f,
-0.0005990413f,-0.0006724584f,-0.0005047619f,-0.0001171406f, 0.0004372104f, 0.0010797374f,
0.0017169949f, 0.0022534601f, 0.0026050371f, 0.0027112878f, 0.0025446519f, 0.0021152693f,
0.0014705327f, 0.0006894468f,-0.0001277897f,-0.0008733366f,-0.0014468246f,-0.0017698095f,
-0.0017974750f,-0.0015259241f,-0.0009938711f,-0.0002783418f, 0.0005151815f, 0.0012669280f,
0.0018594224f, 0.0021942034f, 0.0022063046f, 0.0018744400f, 0.0012252608f, 0.0003308740f,
-0.0006999772f,-0.0017363651f,-0.0026430272f,-0.0032994372f,-0.0036172996f,-0.0035539945f,
-0.0031199655f,-0.0023787848f,-0.0014397352f,-0.0004436511f, 0.0004561031f, 0.0011150128f,
0.0014181900f, 0.0012975421f, 0.0007428372f,-0.0001950981f,-0.0014097317f,-0.0027521917f,
-0.0040510049f,-0.0051355902f,-0.0058603728f,-0.0061261746f,-0.0058958745f,-0.0052041918f,
-0.0041474660f,-0.0028816782f,-0.0015956931f,-0.0004880525f, 0.0002612250f, 0.0005167695f,
0.0002085432f,-0.0006559859f,-0.0019902208f,-0.0036379161f,-0.0053928385f,-0.0070261631f,
-0.0083180284f,-0.0090889780f,-0.0092268159f,-0.0087049647f,-0.0075894402f,-0.0060330006f,
-0.0042568860f,-0.0025221767f,-0.0010944561f,-0.0002064388f,-0.0000237284f,-0.0006187163f,
-0.0019563607f,-0.0038947756f,-0.0062005014f,-0.0085775775f,-0.0107065383f,-0.0122883661f,
-0.0130875874f,-0.0129684039f,-0.0119185125f,-0.0100567406f,-0.0076227165f,-0.0049491711f,
-0.0024198814f,-0.0004183923f, 0.0007258785f, 0.0007867696f,-0.0003212561f,-0.0025231429f,
-0.0055845169f,-0.0091349479f,-0.0127114002f,-0.0158169578f,-0.0179877599f,-0.0188595572f,
-0.0182248418f,-0.0160724049f,-0.0126028433f,-0.0082166040f,-0.0034743283f, 0.0009670264f,
0.0044354922f, 0.0063335060f, 0.0062244751f, 0.0039053136f,-0.0005450570f,-0.0067487839f,
-0.0140477185f,-0.0215575093f,-0.0282527468f,-0.0330748862f,-0.0350513372f,-0.0334119094f,
-0.0276905793f,-0.0177980957f,-0.0040578279f, 0.0128017918f, 0.0316985253f, 0.0512872217f,
0.0700815899f, 0.0865943871f, 0.0994813474f, 0.1076734313f, 0.1104831570f, 0.1076734313f,
0.0994813474f, 0.0865943871f, 0.0700815899f, 0.0512872217f, 0.0316985253f, 0.0128017918f,
-0.0040578279f,-0.0177980957f,-0.0276905793f,-0.0334119094f,-0.0350513372f,-0.0330748862f,
-0.0282527468f,-0.0215575093f,-0.0140477185f,-0.0067487839f,-0.0005450570f, 0.0039053136f,
0.0062244751f, 0.0063335060f, 0.0044354922f, 0.0009670264f,-0.0034743283f,-0.0082166040f,
-0.0126028433f,-0.0160724049f,-0.0182248418f,-0.0188595572f,-0.0179877599f,-0.0158169578f,
-0.0127114002f,-0.0091349479f,-0.0055845169f,-0.0025231429f,-0.0003212561f, 0.0007867696f,
0.0007258785f,-0.0004183923f,-0.0024198814f,-0.0049491711f,-0.0076227165f,-0.0100567406f,
-0.0119185125f,-0.0129684039f,-0.0130875874f,-0.0122883661f,-0.0107065383f,-0.0085775775f,
-0.0062005014f,-0.0038947756f,-0.0019563607f,-0.0006187163f,-0.0000237284f,-0.0002064388f,
-0.0010944561f,-0.0025221767f,-0.0042568860f,-0.0060330006f,-0.0075894402f,-0.0087049647f,
-0.0092268159f,-0.0090889780f,-0.0083180284f,-0.0070261631f,-0.0053928385f,-0.0036379161f,
-0.0019902208f,-0.0006559859f, 0.0002085432f, 0.0005167695f, 0.0002612250f,-0.0004880525f,
-0.0015956931f,-0.0028816782f,-0.0041474660f,-0.0052041918f,-0.0058958745f,-0.0061261746f,
-0.0058603728f,-0.0051355902f,-0.0040510049f,-0.0027521917f,-0.0014097317f,-0.0001950981f,
0.0007428372f, 0.0012975421f, 0.0014181900f, 0.0011150128f, 0.0004561031f,-0.0004436511f,
-0.0014397352f,-0.0023787848f,-0.0031199655f,-0.0035539945f,-0.0036172996f,-0.0032994372f,
-0.0026430272f,-0.0017363651f,-0.0006999772f, 0.0003308740f, 0.0012252608f, 0.0018744400f,
0.0022063046f, 0.0021942034f, 0.0018594224f, 0.0012669280f, 0.0005151815f,-0.0002783418f,
-0.0009938711f,-0.0015259241f,-0.0017974750f,-0.0017698095f,-0.0014468246f,-0.0008733366f,
-0.0001277897f, 0.0006894468f, 0.0014705327f, 0.0021152693f, 0.0025446519f, 0.0027112878f,
0.0026050371f, 0.0022534601f, 0.0017169949f, 0.0010797374f, 0.0004372104f,-0.0001171406f,
-0.0005047619f,-0.0006724584f,-0.0005990413f,-0.0002974170f, 0.0001880784f, 0.0007886354f,
0.0014211081f, 0.0019998882f, 0.0024488224f, 0.0027114957f, 0.0027584970f, 0.0025907218f,
0.0022384277f, 0.0017563231f, 0.0012155342f, 0.0006935370f, 0.0002619020f,-0.0000211214f,
-0.0001203145f,-0.0000267023f, 0.0002415985f, 0.0006426406f, 0.0011170820f, 0.0015968377f,
0.0020147314f, 0.0023137474f, 0.0024546503f, 0.0024209305f, 0.0022204845f, 0.0018838923f,
0.0014595849f, 0.0010066897f, 0.0005865884f, 0.0002543686f, 0.0000514030f,-0.0000000058f,
0.0001008215f, 0.0003334254f, 0.0006595979f, 0.0010291844f, 0.0013872308f, 0.0016819017f,
0.0018713163f, 0.0019292574f, 0.0018483209f, 0.0016403901f, 0.0013345069f, 0.0009724061f,
0.0006024022f, 0.0002725259f, 0.0000239082f,-0.0001146943f,-0.0001305200f,-0.0000281207f,
0.0001717278f, 0.0004353657f, 0.0007212731f, 0.0009859932f, 0.0011902347f, 0.0013041379f,
0.0013111621f, 0.0012099822f, 0.0010142494f, 0.0007502948f, 0.0004531208f, 0.0001613566f,
-0.0000882146f,-0.0002656412f,-0.0003517550f,-0.0003405009f,-0.0002393698f,-0.0000679871f,
0.0001449418f, 0.0003658605f, 0.0005611468f, 0.0007017674f, 0.0007671322f, 0.0007476677f,
0.0006458134f, 0.0004753909f, 0.0002593430f, 0.0000261329f,-0.0001940102f,-0.0003736551f,
-0.0004916409f,-0.0005359033f,-0.0005048299f,-0.0004071616f,-0.0002604794f,-0.0000884979f,
0.0000823809f, 0.0002268029f, 0.0003239133f, 0.0003600909f, 0.0003306072f, 0.0002399869f,
0.0001011003f,-0.0000668730f,-0.0002412975f,-0.0003992998f,-0.0005209351f,-0.0005918278f,
-0.0006049803f,-0.0005615004f,-0.0004701224f,-0.0003460213f,-0.0002078708f,-0.0000761311f,
0.0000307076f, 0.0000982361f, 0.0001179086f, 0.0000880971f, 0.0000141208f,-0.0000927250f,
-0.0002169625f,-0.0003412138f,-0.0004486501f,-0.0005252710f,-0.0005617283f,-0.0005544731f,
-0.0005060412f,-0.0004245023f,-0.0003221742f,-0.0002137524f,-0.0001142343f,-0.0000368277f,
0.0000087805f, 0.0000176282f,-0.0000100068f,-0.0000688527f,-0.0001495029f,-0.0002399160f,
-0.0003271062f,-0.0003990178f,-0.0004461496f,-0.0004627523f,-0.0004475075f,-0.0004035583f,
-0.0003379262f,-0.0002604090f,-0.0001821358f,-0.0001139975f,-0.0000651581f,-0.0000418429f,
-0.0000465332f,-0.0000777464f,-0.0001303695f,-0.0001963221f,-0.0002658396f,-0.0003287024f,
-0.0003756478f,-0.0003995218f,-0.0003961436f,-0.0003647587f,-0.0003080131f,-0.0002315220f,
-0.0001430419f,-0.0000514436f, 0.0000344273f, 0.0001068279f, 0.0001599822f, 0.0001906737f,
0.0001984728f, 0.0001855962f, 0.0001564562f, 0.0001169578f, 0.0000736751f, 0.0000329934f,
0.0000003593f,-0.0000202947f,-0.0005125820f};
// Messages 0 to 7, 0 is not used
const char* inputString[] = {
"ABCDEFG123456",
"A1AA B1BB -22",
"A1AA B1BB -19",
"A1AA B1BB -16",
"A1AA B1BB -13",
"A1AA B1BB -10",
"A1AA B1BB -7",
"A1AA B1BB -4"};
float32_t pStateArray[1322]; // 2*597+128 for FIR filter
const int ledPin = 13; // Blink LED every 15 sec
uint32_t tMillis;
uint32_t tMillisOffset = 0UL;
void setup(void) {
Serial.begin(9600); delay(500);
Serial.println("FT8Transmit7HP.ino Ver 0.1 25 Oct 2022 W7PUA");
Serial.println("Use '=' to zero FT8 clock.");
AudioMemory_F32(20, audio_settings);
AudioMemory(30);
FT8Mod1.setSampleRate_Hz(48000.0f);
FT8Mod1.ft8Initialize();
FT8Mod1.frequency(700.0f);
// Calibration note: For the following = 0.1 and the GWN amplitude at 0.1,
// the power S/N at the output of the FIR filter is 6.617 dB or
// 4.589 as a power ratio. The filter is very close to a 2500 Hz BW
// so this is close to the WSJT defined S/N. Show on WSJT-X as -1.8 dB S/N.
// (Power as used here means the RMS object output squared.)
FT8Mod1.amplitude(powf(10.0f, 0.05f*(-22-26.617))); // snr = -22 dB
FT8Mod2.setSampleRate_Hz(48000.0f);
FT8Mod2.ft8Initialize();
FT8Mod2.frequency(850.0f);
FT8Mod2.amplitude(powf(10.0f, 0.05f*(-19-26.617))); // snr = -19 dB
FT8Mod3.setSampleRate_Hz(48000.0f);
FT8Mod3.ft8Initialize();
FT8Mod3.frequency(1000.0f);
FT8Mod3.amplitude(powf(10.0f, 0.05f*(-16-26.617))); // snr = -16 dB
FT8Mod4.setSampleRate_Hz(48000.0f);
FT8Mod4.ft8Initialize();
FT8Mod4.frequency(1150.0f);
FT8Mod4.amplitude(powf(10.0f, 0.05f*(-13-26.617))); // snr = -13 dB
FT8Mod5.setSampleRate_Hz(48000.0f);
FT8Mod5.ft8Initialize();
FT8Mod5.frequency(1300.0f);
FT8Mod5.amplitude(powf(10.0f, 0.05f*(-10-26.617))); // snr = -10 dB
FT8Mod6.setSampleRate_Hz(48000.0f);
FT8Mod6.ft8Initialize();
FT8Mod6.frequency(1450.0f);
FT8Mod6.amplitude(powf(10.0f, 0.05f*(-7-26.617))); // snr = -7 dB
FT8Mod7.setSampleRate_Hz(48000.0f);
FT8Mod7.ft8Initialize();
FT8Mod7.frequency(1600.0f);
FT8Mod7.amplitude(powf(10.0f, 0.05f*(-4-26.617))); // snr = -4 dB
filterFIRgeneral1.LoadCoeffs(597, filter2500BP, pStateArray);
GaussianWhiteNoise1.amplitude(0.1f); // Do not change from 0.1f unless breaking the cal is wanted.
sgtl5000_1.enable();
delay(5);
// This is intended as running in the Teensy unattended.
// For this, the clock will just use the millisec() clock.
tMillis = millis();
}
void loop() {
int16_t inCmd;
if( Serial.available() )
{
inCmd = Serial.read();
if(inCmd=='=') //Set local clock to zero
{
tMillis = millis();
tMillisOffset = 0UL;
Serial.println("Clock Zero'd");
}
else if(inCmd=='p' || inCmd=='P') // Increase clock 0.1 sec
{
tMillisOffset += 100UL;
Serial.println("Increase clock 0.1 sec");
}
else if(inCmd=='l' || inCmd=='L') // Decrease clock 0.1 sec
{
tMillisOffset -= 100UL;
Serial.println("Decrease clock 0.1 sec");
}
else if(inCmd=='-') // Increase clock 1 sec
{
tMillisOffset += 1000UL;
Serial.println("Increase clock 1 sec");
}
else if(inCmd==',') // Decrease clock 1 sec
{
tMillisOffset -= 1000UL;
Serial.println("Decrease clock 1 sec");
}
else if(inCmd=='?')
{
Serial.println("= Set local FT-8 clock to 0");
Serial.println("p, P Increase local FT8 clock by 0.1 sec");
Serial.println("l, L Decrease local FT8 clock by 0.1 sec");
Serial.println("- Increase local FT8 clock by 1 sec");
Serial.println(", Decrease local FT8 clock by 1 sec");
Serial.println("? Help Display (this message)");
}
else if(inCmd>35) // Ignore anything below '#'
Serial.println("Cmd ???");
} // End, if Serial Available
// Send every 15 sec
if( !FT8Mod7.FT8TransmitBusy() && ((millis() + tMillisOffset) - tMillis ) >= 15000UL )
{
tMillis += 15000UL;
mixer8_1.gain(0, 1.0f); // Noise
mixer8_1.gain(1, 1.0f);
mixer8_1.gain(2, 1.0f);
mixer8_1.gain(3, 1.0f);
mixer8_1.gain(4, 1.0f);
mixer8_1.gain(5, 1.0f);
mixer8_1.gain(6, 1.0f);
mixer8_1.gain(7, 1.0f);
FT8Mod1.cancelTransmit();
FT8Mod1.sendData((char*) inputString[1], 1, 0, 0);
FT8Mod2.cancelTransmit();
FT8Mod2.sendData((char*) inputString[2], 1, 0, 0);
FT8Mod3.cancelTransmit();
FT8Mod3.sendData((char*) inputString[3], 1, 0, 0);
FT8Mod4.cancelTransmit();
FT8Mod4.sendData((char*) inputString[4], 1, 0, 0);
FT8Mod5.cancelTransmit();
FT8Mod5.sendData((char*) inputString[5], 1, 0, 0);
FT8Mod6.cancelTransmit();
FT8Mod6.sendData((char*) inputString[6], 1, 0, 0);
FT8Mod7.cancelTransmit();
FT8Mod7.sendData((char*) inputString[7], 1, 0, 0);
Serial.println("Send every 15 sec");
digitalWrite(ledPin, HIGH); // set the LED on
delay(100);
digitalWrite(ledPin, LOW); // set the LED on
}
// Turn off
if( !FT8Mod7.FT8TransmitBusy() && (millis() + tMillisOffset) - tMillis >= 13000UL )
{
// mixer8_1.gain(0, 0.0f); // Noise
mixer8_1.gain(1, 0.0f);
mixer8_1.gain(2, 0.0f);
mixer8_1.gain(3, 0.0f);
mixer8_1.gain(4, 0.0f);
mixer8_1.gain(5, 0.0f);
mixer8_1.gain(6, 0.0f);
mixer8_1.gain(7, 0.0f);
}
} // End. loop

Binary file not shown.

@ -0,0 +1,213 @@
/*
* radioFT8Demodulator_F32.cpp Assembled by Bob Larkin 8 Sept 2022
*
* This class is Teensy 4.x ONLY.
*
* Copyright (c) 2021 Bob Larkin
*
* 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, development funding 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.
*/
/* Sampling (for 96 kHz case):
* Every 5 audio samples at 96 kHz produce 1 19.2 kHz sample
* Every 3 audio samples at 19.2 produce 1 6.4 kHz sample
* Every 15*128=1920 audio samples at 96 kHz produce 128 samples at 6.4 kHz
*
* Every 120 (for 48 kHz) or 60 (for 96 kHz) blocks produces 1024 data points
* at 6.4 kHz reduced sample rate. This 1024 size is sent to the .INO as it
* is *half* of a 2048 data block, and thus supports 50% overlap FFT's.
*
*/
// ******************* TEENSY 4.x ONLY *******************
#if defined(__IMXRT1062__)
#include <Arduino.h>
#include "radioFT8Demodulator_F32.h"
// decimate15() is common code for several cases of decimation.
// Input is 128 word of data, in outFIR1,
// ready to be decimated by 15 to FT8 6.4 kHz sample rate.
void radioFT8Demodulator_F32::decimate15(void) {
// Stage 1, decimate by 5.
// current128Used1 = true means that outFIR1[] is empty
// current128Used1 = false means that outFIR1[] has some content
// For 48 kHz sample rate, here twice every 2.6667 milliseconds
while(!current128Used1) // While we still have filtered input data
{
// Every time here dec1Count grows by 51.2, i.e., by 2*128/5 mod 128
inFIR2[dec1Count++] = outFIR1[kOffset1]; // The 5th sample
kOffset1 += 5; // Update offset
if(kOffset1>127) // We have run out of source data for now
{
kOffset1 -= 128; // For the next 128
current128Used1 = true;
}
if(dec1Count >= 128) // Time to do second FIR filter
{
// Here twice every 13.3 millisec, 2*2.66667*2.5=13.3333
arm_fir_f32(&fir_inst2, inFIR2, outFIR2, 128);
current128Used2 = false; // Just filled outFIR2[]
dec1Count = 0;
// Have 128 samples from the first divide by 5 stage, filtered
// and ready for divide by 3.
// current128Used2 = true means that outFIR2[] is empty
// current128Used2 = false means that outFIR2[] has some content
while(!current128Used2) // Over all outputs of FIR2
{
outData[dec2Count++] = outFIR2[kOffset2]; // Every 3rd sample
kOffset2 += 3; // Update offset for decimate by 3
if(kOffset2 > 127) // We have run out of stage 2 data
{
kOffset2 -= 128; // For the next 128
current128Used2 = true;
}
if(dec2Count >= 128) // 128 block is ready
{
// Arrive here about every 20 millisec (twice per 40.000) 18.7, 21.3
dec2Count = 0;
// Bonus power calculation. Takes about 5 uSec
powerOut = 0.0f;
for(int kk=0; kk<128; kk++)
{
powerOut += (outData[kk]*outData[kk]); // Power
}
powerOut = 10.0f*log10f(powerOut) - 21.072f; // in dB, corrected for 128
powAvail = true;
#ifdef W5BAA_INTERFACE
block = allocate(); // Get 128 int16 block for queue out
if (!block)
return;
h = head + 1;
if (h >= max_buffers)
h = 0;
if (h == tail) // Ooops, ran out of queue memory blocks
AudioStream::release(block);
else // Fill the block data
{
for(int kk=0; kk<128; kk++)
{
block->data[kk] = (int)(32768.0f*outData[kk]); // Output signal
}
queue[h] = block;
head = h;
// current128Used2 = false;
}
#else
// Not W5BAA interface, i.e., 512 floats at a time.
// To allow correction for time and frequency, the FT8 synch system performs
// FFT every 80 mSec with frequency steps of 3.125 Hz. 80 mSec at 6400
// samples/sec is 512 samples. Thus data is sent from this class after
// 512 samples. The data set is 2048 floats.
// At 6400 decimated samples/sec, it takes 128/6400=0.02 sec to fill
// outData[128]. The data2k[2048] will be re-used after that time
// which should be plenty adequate for the FFT to be done. Be sure that
// that the FFT is not delayed a large amount.
// FFT is 2048, but we need overlap every 512 points.
// Next is the 2048 FFT input data buffer. Shift 512
// and add in the Temp 512 data pts.
if(block128Count==0)
{
for (int kk=0; kk<1536; kk++)
{
data2K[kk] = data2K[kk + 512]; // Shift 512
}
}
for(int kk=0; kk<128; kk++)
data2K[1536 + 128*block128Count + kk] = outData[kk];
if(block128Count++ >= 3) // Time to send data for FFT
{
block128Count = 0;
index2 = 0;
outputFlag = true;
FFTCount++; // Count of incoming samples in units of 512
if(FFTCount >= 184)
{
dec1Count = 0;
dec2Count = 0;
index2 = 0;
//FFTCount = 0; // Reset by startDataCollect(void)
gettingData = false;
}
} // End, time to make 512 data pts available
#endif
} // End if(dec2Count >= 128)
} // End, inner while(), i.e., while(!current128Used2)
}
} // End, while have input data
}
// Note: Suppports block size of 128 only. Very "built in."
void radioFT8Demodulator_F32::update(void) {
audio_block_f32_t *block_in;
int ii;
if(!gettingData)
return;
block_in = receiveReadOnly_f32(0);
if (srIndex==SR_NONE || !block_in) { Serial.println("Block error"); return; }
// ttt=micros();
// Here every 2.6667 millisec for 48 kHz, 128 pts
current128Used1 = false; // There are 128 new input data to use
if(srIndex == SR48000)
{
for(int k=0; k<64; k++) // Over half the current block of samples
{
// Make next 2 same. Linearty of Fourier transform says
// the result is the same either transform x2 in magnitude.
dataIn[2*k] = 0.5f*block_in->data[k];
dataIn[2*k+1] = 0.5f*block_in->data[k];
}
arm_fir_f32(&fir_inst1, dataIn, outFIR1, 128); // LP filter <9600 Hz
current128Used1 = false; // Just created 128 in outFIR1
decimate15();
for(int k=64; k<128; k++) // Ditto over the second half of samples
{
dataIn[2*k-128] = 0.5f*block_in->data[k];
dataIn[2*k-127] = 0.5f*block_in->data[k];
}
arm_fir_f32(&fir_inst1, dataIn, outFIR1, 128); // LP filter <9600 Hz
current128Used1 = false; // Just created a second 128, outFIR1
decimate15();
}
else // SR_INDEX == SR96000
{
arm_fir_f32(&fir_inst1, block_in->data, outFIR1, 128); // LP filter
decimate15();
}
AudioStream_F32::release(block_in);
#ifndef W5BAA_INTERFACE
if(FFTCount>FFTOld)
{ FFTOld=FFTCount; }
#endif
// Serial.print("time usec "); Serial.println(micros()-ttt);
} // End update()
#endif

@ -0,0 +1,407 @@
/*
* radioFT8Demodulator_F32.h Assembled by Bob Larkin 11 Sept 2022
*
* Note: Teensy 4.x Only, 3.x not supported
*
* (c) 2021 Bob Larkin
*
* 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, development funding 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.
*/
/* *** CREDITS ***
* There have been many contributors to this FT8 project. I will not
* catch them all, but a try is neeeded. I picked from
* multiple sources in making the transmission process consistent with the
* 128-block Teensy Audio Library. But, everything I did was a translation
* of existing software. The "specification" for FT8 is the paper, "The FT4
* and FT8 Communications Protocols," by Steve Franke, K9AN, Bill Somerville,
* G4WJS and Joe Taylor, K1JT, QEX July/August 2020, pp7-17. I was guided
* in the right direction for this implementation by Farhan, VU2ESE
* and Charlie, W5BAA. This led to a pair of excellent Raspberry Pi sources,
* https://github.com/kgoba/ft8_lib and
* https://github.com/WB2CBA/W5BAA-FT8-POCKET-TERMINAL
* An FT8 derivative of the first web site, using the Raspberry Pi,
* is Farhan's sBitx:
* https://github.com/afarhan/sbitx
* For those not familiar with FT8, it is a widely used amateur radio
* communications format. A search of FT8 will lead to much information.
*
* Notes:
* 1. Sampling rate: The entire FT8 Demodulator runs at a decimated
* 6400 samples/sec. At this time, only 48 and 96 kHz sample rates are
* supported. For 48 kHz there is
* an interpolate to 96 kHz followed by decimation to 19.2 and 6.4 kHz.
* For 96 kHz there is no interpolation.
*
* 2. In order to process the decoding of FT8 as rapidly as possibly,
* after the 0.16 seconds of data are acquired (2048 data points),
* this library class only does the process that must be done in real
* time, either because of data un-availability or because the full data
* set for 0.16 sec is needed. Thus this class does the two stages
* of decimation in time needed to reduce the data rate and does the
* saving of signal samples to an array.
*
* 3. To allow two FFT's, offset in time by 0.16sec / 2, we need to gather
* 2048 data points every 0.08 seconds with 50% overlap in data.
* These are put into an array that is supplied by the calling
* INO/CPP program. It is arrange as signalData[2][1024]
* for convenience. The indices of the first of two is returned
* when data is available. In order to not need dual large storage, an
* 18 float auxiliary storage is provided to store data acquired during
* the "first two" update period (5.3 or 2.7 mSec for 48 or
* 96 kHz sample rate). This gives time for an FFT
* before altering the signal data.
*
* 4. This class does not provide true (absolute) clock timing.
* The startReceive() function should be called when it is time
* for a new reception period. This class will start that at the
* next 128 audio sample period.
*
* 5. Update time required for a T4.x is uSec.
*/
// The Charlie Hill W5BAA_INTERFACE is from the Pocket-FT9 project and
// transfers data as 128 int's. It is included as a compile time
// option to allow testing with the Pocket-FT8 Teensy software.
// The default interface transfers the collected data as a pointer to
// 2048 F32 float's ready for windowing and FFT's. Both
// interfaces includes 50% overlap of the data to correct for window losses.
// #define W5BAA_INTERFACE
#ifndef radioFT8Demodulator_h_
#define radioFT8Demodulator_h_
#define SR_NONE 0
#define SR48000 1
#define SR96000 2
// *************** TEENSY 4.X ONLY ****************
#if defined(__IMXRT1062__)
#include "Arduino.h"
#include "AudioStream_F32.h"
#include "arm_math.h"
class radioFT8Demodulator_F32 : public AudioStream_F32 {
//GUI: inputs:2, outputs:4 //this line used for automatic generation of GUI node
//GUI: shortName:FFT2048IQ
public:
radioFT8Demodulator_F32() : AudioStream_F32(1, inputQueueArray_f32) {
}
// There is no varient for "settings," as blocks other than 128 are
// not supported FIX. <<<<<<<<<<<<<<<<<<<<<
void initialize(void) {
// Initialize 2 FIR instances (ARM DSP Math Library)
//arm_fir_init_f32 (arm_fir_instance_f32 *S, uint16_t numTaps,
const float32_t *pCoeffs, float32_t *pState, uint32_t blockSize)
arm_fir_init_f32(&fir_inst1, 55, &firDecimate1[0], &dec1FIRWork[0], 128UL);
arm_fir_init_f32(&fir_inst2, 167, &firDecimate2[0], &dec2FIRWork[0], 128UL);
// CHECK SAMPLE RATE AND SET index <<<<<<<<<<<<<
FT8DemodInit = true;
#ifdef W5BAA_INTERFACE
gettingData = true;
#endif
}
// Following reflects that there are only 2 supported sample rates.
// IMPORTANT: This changes constants for FT8 Transmit, only. It does not
// change system-wide audio sample rate. Use AudioSettings_F32.
void setSampleRate_Hz(const float32_t &fs_Hz) {
sampleRateHz = fs_Hz;
if(sampleRateHz>47900.0f && sampleRateHz<48100.0f)
{
sampleRateHz = 48000.0f;
srIndex = SR48000;
}
else if(sampleRateHz>95900.0f && sampleRateHz<96100.0f)
{
sampleRateHz = 96000.0f;
srIndex = SR96000;
}
else
{
Serial.println("Unsupported sample rate, FT-8 will not receive.");\
srIndex = SR_NONE;
}
}
void decimate15(void);
bool powerAvailable(void) {
if(powAvail) return true;
return false;
}
// Read the dB power level *once* per 128 samples at 6.4kHz
float32_t powerRead(void) {
if(powAvail)
{
powAvail = false;
return powerOut;
}
else
return -200.0f;
}
#ifdef W5BAA_INTERFACE
int queueAvailable(void) { // W5BAA_INTERFACE only
uint32_t h, t;
h = head;
t = tail; //Serial.print("@queueAvailable h, t= "); Serial.print(h); Serial.print(", "); Serial.println(t);
if (h >= t)
return h - t;
return max_buffers + h - t;
}
void queueClear(void) { // W5BAA_INTERFACE only
uint32_t t;
if (userblock)
{
AudioStream::release(userblock);
userblock = NULL;
}
t = tail;
while (t != head)
{
if (++t >= max_buffers)
t = 0;
AudioStream::release(queue[t]);
}
tail = t;
}
int16_t* queueReadBuffer(void) { // W5BAA_INTERFACE only
uint32_t t;
if (userblock)
return NULL;
t = tail;
if (t == head)
return NULL;
if (++t >= max_buffers)
t = 0;
userblock = queue[t];
tail = t;
return userblock->data; // Pointer to 128 int16_t of data
}
void queueFreeBuffer(void) { // W5BAA_INTERFACE only
if (userblock == NULL)
return;
AudioStream::release(userblock);
userblock = NULL;
}
#else
// Regular 512/2048 float interface
// Returns true when output data is available.
bool available() {
if (outputFlag == true)
{
outputFlag = false; // No double returns
return true;
}
return false;
}
// Start a new 14.7 sec data gather
void startDataCollect(void) {
gettingData = true;
FFTCount = 0;
dec1Count = 0;
dec2Count = 0;
kOffset1 = 0;
kOffset2 = 0;
outputFlag = false;
current128Used1 = false;
current128Used2 = false;
FFTCount = 0;
FFTOld = 0;
block128Count = 0;
index2 = 0; // Runs 0,511 on outputs
}
// Cancel the data gather
void cancelDataCollect(void) {
gettingData = false;
// Getting started again from here is by startDataCollect()
}
bool receivingData(void) {
return gettingData;
}
// Return FFT Count, 0 = No data
// 1 to 184 = current 1024 words last returned
// The number is incremented every 80 mSec during receive
// Reset to 0 is by startDataCollect()
int getFFTCount(void) {
return FFTCount;
}
float32_t* getDataPtr(void) { // Location of input for FFT
return &data2K[0];
}
#endif
virtual void update(void);
private:
audio_block_f32_t *inputQueueArray_f32[1];
float sampleRateHz = AUDIO_SAMPLE_RATE;
int16_t srIndex = SR_NONE;
//uint16_t block_size = 128;
int16_t fcurrentArray = -1;
float32_t *p0 = NULL; // Pointers to 1024 storage
float32_t *p1 = NULL;
uint32_t ttt;
int32_t kkk;
bool FT8DemodInit = false;
bool outputFlag = false;
bool gettingData = false;
bool current128Used1 = false; // Decimation by 5
bool current128Used2 = false; // Decimation by 3
audio_block_f32_t *inputQueueArray[1];
int32_t dec1Count = 0;
int32_t dec2Count = 0;
float32_t dataIn[128];
float32_t inFIR1[128]; // Inputs for FIR1
// Working space for 55-tap FIR, 128 data points
float32_t dec1FIRWork[183];
float32_t outFIR1[128];
int kOffset1 = 0;
float32_t inFIR2[128];
// Working space for 167-tap FIR
float32_t dec2FIRWork[295];
float32_t outFIR2[128];
int kOffset2 = 0;
arm_fir_instance_f32 fir_inst1, fir_inst2;
bool powAvail = false;
float32_t powerOut = 0.0f;
float32_t outData[128]; // Storage after decimate by 3
#ifdef W5BAA_INTERFACE
static const int max_buffers = 48; // Enough for 3 FFT, i.e., plenty
audio_block_t* volatile queue[max_buffers];
audio_block_t* userblock;
volatile uint8_t head = 0;
volatile uint8_t tail = 0;
volatile uint8_t enabled = 0;
audio_block_t *block;
uint32_t h;
#else
int16_t FFTCount = 0;
int FFTOld = 0;
int16_t block128Count = 0;
int16_t index2 = 0; // Runs 0,511 on outputs
float32_t data2K[2048]; // Output time array to FFT 2048+512
#endif
// int64_t sampleCount = 0LL;
// bool sampleCountOdd = false;
/* FOR INFO ONLY
// Blackman-Harris produces a first sidelobe more than 90 dB down.
// The price is a bandwidth of about 2 bins. Very useful at times.
void useBHWindow(void) {
for (int i=0; i < 2048; i++) {
float kx = 0.00306946f; // 2*PI/2047
int ix = (float) i;
window[i] = 0.35875 -
0.48829*cosf( kx*ix) +
0.14128*cosf(2.0f*kx*ix) -
0.01168*cosf(3.0f*kx*ix);
}
}
*/
/* FIR filter designed with http://t-filter.appspot.com
* Sampling frequency = 96000 Hz
* 0 Hz - 3200 Hz ripple = 0.065 dB
* 9600 Hz - 48000 Hz att = -81.1 dB */
const float32_t firDecimate1[55] = { // constexpr static
0.000037640f, 0.000248621f, 0.000535682f, 0.001017563f, 0.001647298,
0.002359693f, 0.003009942f, 0.003388980f, 0.003245855f, 0.002335195,
0.000482309f, -0.002343975f, -0.005965316f, -0.009953093f, -0.013627779f,
-0.016110493f, -0.016426909f, -0.013654288f, -0.007090645f, 0.003582981f,
0.018178902f, 0.035947300f, 0.055606527f, 0.075464728f, 0.093619230f,
0.108205411f, 0.117656340f, 0.120928651f, 0.117656340f, 0.108205411f,
0.093619230f, 0.075464728f, 0.055606527f, 0.035947300f, 0.018178902f,
0.003582981f, -0.007090645f, -0.013654288f, -0.016426909f, -0.016110493f,
-0.013627779f, -0.009953093f, -0.005965316f, -0.002343975f, 0.000482309f,
0.002335195f, 0.003245855f, 0.003388980f, 0.003009942f, 0.002359693f,
0.001647298f, 0.001017563f, 0.000535682f, 0.000248621f, 0.000037640f};
/* FIR filter designed with http://t-filter.appspot.com
* Sampling frequency = 19200 Hz
* 0 Hz - 2800 Hz ripple = 0.073 dB
* 3200 Hz - 9600 Hz att = -80.0 dB */
const float32_t firDecimate2[167] = {
0.000200074f, 0.000438821f, 0.000648425f, 0.000636175f, 0.000315069f,
-0.000193500f, -0.000591064f, -0.000600896f, -0.000202482f, 0.000301473f,
0.000486276f, 0.000152104f, -0.000466930f, -0.000846593f, -0.000601871f,
0.000140985f, 0.000780434f, 0.000717692f, -0.000092419f, -0.001015260f,
-0.001218073f, -0.000407595f, 0.000820258f, 0.001400419f, 0.000712814f,
-0.000783775f, -0.001824384f, -0.001392096f, 0.000312681f, 0.001894843f,
0.001890948f, 0.000105692f, -0.002046807f, -0.002639347f, -0.000937478f,
0.001779635f, 0.003148244f, 0.001757989f, -0.001441273f, -0.003731905f,
-0.002912877f, 0.000623820f, 0.003953823f, 0.004009904f, 0.000373714f,
-0.004041709f, -0.005284541f, -0.001864153f, 0.003610036f, 0.006359221f,
0.003566059f, -0.002829631f, -0.007374880f, -0.005699305f, 0.001364774f,
0.007956768f, 0.007979137f, 0.000650460f, -0.008163693f, -0.010542154f,
-0.003518210f, 0.007604450f, 0.013094981f, 0.007160556f, -0.006233941f,
-0.015716023f, -0.011940068f, 0.003541776f, 0.018116367f, 0.018029298f,
0.000861510f, -0.020344029f, -0.026351929f, -0.008277630f, 0.022137232f,
0.038780109f, 0.021608602f, -0.023552791f, -0.062590967f, -0.053225138f,
0.024375124f, 0.148263262f, 0.262405223f, 0.308632386f, 0.262405223f,
0.148263262f, 0.024375124f, -0.053225138f, -0.062590967f, -0.023552791f,
0.021608602f, 0.038780109f, 0.022137232f, -0.008277630f, -0.026351929f,
-0.020344029f, 0.000861510f, 0.018029298f, 0.018116367f, 0.003541776f,
-0.011940068f, -0.015716023f, -0.006233941f, 0.007160556f, 0.013094981f,
0.007604450f, -0.003518210f, -0.010542154f, -0.008163693f, 0.000650460f,
0.007979137f, 0.007956768f, 0.001364774f, -0.005699305f, -0.007374880f,
-0.002829631f, 0.003566059f, 0.006359221f, 0.003610036f, -0.001864153f,
-0.005284541f, -0.004041709f, 0.000373714f, 0.004009904f, 0.003953823f,
0.000623820f, -0.002912877f, -0.003731905f, -0.001441273f, 0.001757989f,
0.003148244f, 0.001779635f, -0.000937478f, -0.002639347f, -0.002046807f,
0.000105692f, 0.001890948f, 0.001894843f, 0.000312681f, -0.001392096f,
-0.001824384f, -0.000783775f, 0.000712814f, 0.001400419f, 0.000820258f,
-0.000407595f, -0.001218073f, -0.001015260f, -0.000092419f, 0.000717692f,
0.000780434f, 0.000140985f, -0.000601871f, -0.000846593f, -0.000466930f,
0.000152104f, 0.000486276f, 0.000301473f, -0.000202482f, -0.000600896f,
-0.000591064f, -0.000193500f, 0.000315069f, 0.000636175f, 0.000648425f,
0.000438821f, 0.000200074f};
// endif for Teensy 4.x only and for single read of .h file:
#endif
}; // End class def
#endif
Loading…
Cancel
Save