Porównaj commity

...

23 Commity

Autor SHA1 Wiadomość Data
Rob Riggs 9e6f588d30 Update to version 2.4.4. Clock recovery improvements. Update the sample index more frequently to reduce EVM. Re-wrote the symbol deviation, offset, EVM code. More code comments. 2022-05-29 17:09:09 -05:00
Rob Riggs a85cbf0baa Add BOM for rev C PCB. 2022-02-20 12:14:19 -06:00
Rob Riggs 4df32f232a Update README.md for Blaze dependency. 2022-01-23 15:09:08 -06:00
Rob Riggs 6a5010dc55 Make the adcInputQueue size match the number of buffers allocated in AudioInput.hpp (8). 2022-01-23 15:08:45 -06:00
Rob Riggs 9158fe45af Update firmware version to 2.4.3. 2022-01-23 15:06:57 -06:00
Rob Riggs f4ac271109 Change clock used for M17 to 48MHz. 2022-01-23 15:06:46 -06:00
Rob Riggs 077c00917b Update FT-991 config. 2022-01-23 15:06:35 -06:00
Rob Riggs 23713d9ed3 Use EOT sync word for end of stream rather than EOS bit. Use only sync word and Kalman filter for clock recovery. Simplify some of the state transistions. Reduce DCD limits since we can follow symbol clock at lower levels now. Use a smaller FIR filter for RRC. 2022-01-23 15:05:20 -06:00
Rob Riggs b5d19da1ad Add feature to allow forced DCD unlocking to aid in modem recycling. 2022-01-23 15:05:20 -06:00
Rob Riggs 55d94ef38d Allow more time for DC offset to settle. 2022-01-23 15:05:20 -06:00
Rob Riggs 17a0e74d46 Add missing include. 2022-01-23 15:05:20 -06:00
Rob Riggs 323e840fa3 Add symbol slope integrator code (currently unused). 2022-01-23 15:05:20 -06:00
Rob Riggs 51b91c4b71 Add Kalman filter code. This adds a dependency on Blaze and requires that exceptions be enabled. 2022-01-23 15:05:20 -06:00
Rob Riggs bcd6d67763 Update firmware version to 2.4.2. 2022-01-23 15:03:38 -06:00
Rob Riggs 4ac0001549 Use an 8-symbol length FIR filter for symbol interpolation. 2022-01-23 15:03:38 -06:00
Rob Riggs 59783338c8 Add reset() function to IIR filter. 2022-01-23 15:03:38 -06:00
Rob Riggs a8296cbdca The FirFilter constructor and init function do not need to be templatized. 2022-01-23 15:03:37 -06:00
Rob Riggs 9a65906f5c Trivial optimization to Viterbi. 2022-01-23 15:03:37 -06:00
Rob Riggs 6d6253f2d1 Add 8 and 11 symbol RRC filters to M17 demod. 2022-01-23 15:03:37 -06:00
Rob Riggs 86a9896a8d Validate the LICH fragment number and mask the LICH segment bitfield properly. Send -1 for BER while LICH decode is incomplete. 2022-01-23 15:03:37 -06:00
Rob Riggs 6c092b9365 Update FT-991 setup. 2022-01-23 15:03:37 -06:00
Rob Riggs 2b5c5497ed Small update to docs. 2022-01-23 15:03:37 -06:00
Rob Riggs 6126fd7af6 Add M17 Setup Guide. 2022-01-23 15:03:37 -06:00
38 zmienionych plików z 5524 dodań i 433 usunięć

File diff suppressed because one or more lines are too long

Wyświetl plik

@ -1,6 +1,6 @@
#MicroXplorer Configuration settings - do not modify
VP_RCC_LSE.Signal=RCC_LSE
FREERTOS.Queues01=ioEventQueue,16,uint32_t,0,Static,ioEventQueueBuffer,ioEventQueueControlBlock;serialInputQueue,16,uint32_t,0,Static,serialInputQueueBuffer,serialInputQueueControlBlock;serialOutputQueue,16,uint32_t,0,Static,serialOutputQueueBuffer,serialOutputQueueControlBlock;audioInputQueue,8,uint32_t,0,Static,audioInputQueueBuffer,audioInputQueueControlBlock;hdlcInputQueue,3,uint32_t,0,Static,hdlcInputQueueBuffer,hdlcInputQueueControlBlock;hdlcOutputQueue,3,uint32_t,0,Static,hdlcOutputQueueBuffer,hdlcOutputQueueControlBlock;dacOutputQueue,128,uint8_t,0,Static,dacOutputQueueBuffer,dacOutputQueueControlBlock;adcInputQueue,3,uint32_t,0,Static,adcInputQueueBuffer,adcInputQueueControlBlock
FREERTOS.Queues01=ioEventQueue,16,uint32_t,0,Static,ioEventQueueBuffer,ioEventQueueControlBlock;serialInputQueue,16,uint32_t,0,Static,serialInputQueueBuffer,serialInputQueueControlBlock;serialOutputQueue,16,uint32_t,0,Static,serialOutputQueueBuffer,serialOutputQueueControlBlock;audioInputQueue,8,uint32_t,0,Static,audioInputQueueBuffer,audioInputQueueControlBlock;hdlcInputQueue,3,uint32_t,0,Static,hdlcInputQueueBuffer,hdlcInputQueueControlBlock;hdlcOutputQueue,3,uint32_t,0,Static,hdlcOutputQueueBuffer,hdlcOutputQueueControlBlock;dacOutputQueue,128,uint8_t,0,Static,dacOutputQueueBuffer,dacOutputQueueControlBlock;adcInputQueue,8,uint32_t,0,Static,adcInputQueueBuffer,adcInputQueueControlBlock
VP_RCC_LSE.Mode=CRS SYNC Source LSE
PA15\ (JTDI).GPIOParameters=GPIO_Label
RCC.USART1Freq_Value=48000000

Wyświetl plik

@ -13,6 +13,19 @@ build the firmware using the same compiler and linker options. As
with most firmware projects, there is a linker script with defines
the memory layout for for the Flash and SRAM.
## Blaze Dependency
There is a new dependency as of 2.4.3 with the addition of the Kalman
filter. The firmware has a dependency on the Blaze C++ math library.
mkdir blaze
ln -s /usr/include/blaze blaze/
This also requires (for now) that the firmware be built with exceptions
enabled.
## Example GCC Command-line
Below are example compilation and linking lines for reference:
arm-none-eabi-g++ -mcpu=cortex-m4 -mthumb -mfloat-abi=softfp -mfpu=fpv4-sp-d16 -O2 -fmessage-length=0 -fsigned-char -ffunction-sections -fdata-sections -fno-inline-functions -fsingle-precision-constant -fstack-usage -fstrict-aliasing -ffast-math -Wall -Wextra -Wlogical-op -Wfloat-equal -g -D__FPU_PRESENT=1 -DUSE_HAL_DRIVER -DARM_MATH_CM4 -DSTM32L432xx -D__weak=__attribute__((weak)) -DNUCLEOTNC=1 -I../Inc -I../Drivers/STM32L4xx_HAL_Driver/Inc -I/home/rob/workspace/Nucleo_L432KC_TNC/Inc -I/home/rob/workspace/Nucleo_L432KC_TNC/Drivers/STM32L4xx_HAL_Driver/Inc -I/home/rob/workspace/Nucleo_L432KC_TNC/Drivers/CMSIS/Include -I/home/rob/workspace/Nucleo_L432KC_TNC/Drivers/CMSIS/Device/ST/STM32L4xx/Include -I/home/rob/workspace/Nucleo_L432KC_TNC/Middlewares/Third_Party/FreeRTOS/Source/include -I/home/rob/workspace/Nucleo_L432KC_TNC/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS -I/home/rob/workspace/Nucleo_L432KC_TNC/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F -I/home/rob/workspace/Nucleo_L432KC_TNC/TNC -I/usr/arm-none-eabi/include -std=gnu++1z -fabi-version=9 -fno-exceptions -fno-rtti -fno-use-cxa-atexit -fno-threadsafe-statics -Wno-register -c -o TNC/HdlcFrame.o ../TNC/HdlcFrame.cpp

647
Src/arm_conv_f32.c 100644
Wyświetl plik

@ -0,0 +1,647 @@
/* ----------------------------------------------------------------------------
* Copyright (C) 2010-2014 ARM Limited. All rights reserved.
*
* $Date: 19. March 2015
* $Revision: V.1.4.5
*
* Project: CMSIS DSP Library
* Title: arm_conv_f32.c
*
* Description: Convolution of floating-point sequences.
*
* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* - Neither the name of ARM LIMITED nor the names of its contributors
* may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
* -------------------------------------------------------------------------- */
#include "arm_math.h"
/**
* @ingroup groupFilters
*/
/**
* @defgroup Conv Convolution
*
* Convolution is a mathematical operation that operates on two finite length vectors to generate a finite length output vector.
* Convolution is similar to correlation and is frequently used in filtering and data analysis.
* The CMSIS DSP library contains functions for convolving Q7, Q15, Q31, and floating-point data types.
* The library also provides fast versions of the Q15 and Q31 functions on Cortex-M4 and Cortex-M3.
*
* \par Algorithm
* Let <code>a[n]</code> and <code>b[n]</code> be sequences of length <code>srcALen</code> and <code>srcBLen</code> samples respectively.
* Then the convolution
*
* <pre>
* c[n] = a[n] * b[n]
* </pre>
*
* \par
* is defined as
* \image html ConvolutionEquation.gif
* \par
* Note that <code>c[n]</code> is of length <code>srcALen + srcBLen - 1</code> and is defined over the interval <code>n=0, 1, 2, ..., srcALen + srcBLen - 2</code>.
* <code>pSrcA</code> points to the first input vector of length <code>srcALen</code> and
* <code>pSrcB</code> points to the second input vector of length <code>srcBLen</code>.
* The output result is written to <code>pDst</code> and the calling function must allocate <code>srcALen+srcBLen-1</code> words for the result.
*
* \par
* Conceptually, when two signals <code>a[n]</code> and <code>b[n]</code> are convolved,
* the signal <code>b[n]</code> slides over <code>a[n]</code>.
* For each offset \c n, the overlapping portions of a[n] and b[n] are multiplied and summed together.
*
* \par
* Note that convolution is a commutative operation:
*
* <pre>
* a[n] * b[n] = b[n] * a[n].
* </pre>
*
* \par
* This means that switching the A and B arguments to the convolution functions has no effect.
*
* <b>Fixed-Point Behavior</b>
*
* \par
* Convolution requires summing up a large number of intermediate products.
* As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation.
* Refer to the function specific documentation below for further details of the particular algorithm used.
*
*
* <b>Fast Versions</b>
*
* \par
* Fast versions are supported for Q31 and Q15. Cycles for Fast versions are less compared to Q31 and Q15 of conv and the design requires
* the input signals should be scaled down to avoid intermediate overflows.
*
*
* <b>Opt Versions</b>
*
* \par
* Opt versions are supported for Q15 and Q7. Design uses internal scratch buffer for getting good optimisation.
* These versions are optimised in cycles and consumes more memory(Scratch memory) compared to Q15 and Q7 versions
*/
/**
* @addtogroup Conv
* @{
*/
/**
* @brief Convolution of floating-point sequences.
* @param[in] *pSrcA points to the first input sequence.
* @param[in] srcALen length of the first input sequence.
* @param[in] *pSrcB points to the second input sequence.
* @param[in] srcBLen length of the second input sequence.
* @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
* @return none.
*/
void arm_conv_f32(
float32_t * pSrcA,
uint32_t srcALen,
float32_t * pSrcB,
uint32_t srcBLen,
float32_t * pDst)
{
#ifndef ARM_MATH_CM0_FAMILY
/* Run the below code for Cortex-M4 and Cortex-M3 */
float32_t *pIn1; /* inputA pointer */
float32_t *pIn2; /* inputB pointer */
float32_t *pOut = pDst; /* output pointer */
float32_t *px; /* Intermediate inputA pointer */
float32_t *py; /* Intermediate inputB pointer */
float32_t *pSrc1, *pSrc2; /* Intermediate pointers */
float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */
float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */
uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counters */
/* The algorithm implementation is based on the lengths of the inputs. */
/* srcB is always made to slide across srcA. */
/* So srcBLen is always considered as shorter or equal to srcALen */
if(srcALen >= srcBLen)
{
/* Initialization of inputA pointer */
pIn1 = pSrcA;
/* Initialization of inputB pointer */
pIn2 = pSrcB;
}
else
{
/* Initialization of inputA pointer */
pIn1 = pSrcB;
/* Initialization of inputB pointer */
pIn2 = pSrcA;
/* srcBLen is always considered as shorter or equal to srcALen */
j = srcBLen;
srcBLen = srcALen;
srcALen = j;
}
/* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */
/* The function is internally
* divided into three stages according to the number of multiplications that has to be
* taken place between inputA samples and inputB samples. In the first stage of the
* algorithm, the multiplications increase by one for every iteration.
* In the second stage of the algorithm, srcBLen number of multiplications are done.
* In the third stage of the algorithm, the multiplications decrease by one
* for every iteration. */
/* The algorithm is implemented in three stages.
The loop counters of each stage is initiated here. */
blockSize1 = srcBLen - 1u;
blockSize2 = srcALen - (srcBLen - 1u);
blockSize3 = blockSize1;
/* --------------------------
* initializations of stage1
* -------------------------*/
/* sum = x[0] * y[0]
* sum = x[0] * y[1] + x[1] * y[0]
* ....
* sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0]
*/
/* In this stage the MAC operations are increased by 1 for every iteration.
The count variable holds the number of MAC operations performed */
count = 1u;
/* Working pointer of inputA */
px = pIn1;
/* Working pointer of inputB */
py = pIn2;
/* ------------------------
* Stage1 process
* ----------------------*/
/* The first stage starts here */
while(blockSize1 > 0u)
{
/* Accumulator is made zero for every iteration */
sum = 0.0f;
/* Apply loop unrolling and compute 4 MACs simultaneously. */
k = count >> 2u;
/* First part of the processing with loop unrolling. Compute 4 MACs at a time.
** a second loop below computes MACs for the remaining 1 to 3 samples. */
while(k > 0u)
{
/* x[0] * y[srcBLen - 1] */
sum += *px++ * *py--;
/* x[1] * y[srcBLen - 2] */
sum += *px++ * *py--;
/* x[2] * y[srcBLen - 3] */
sum += *px++ * *py--;
/* x[3] * y[srcBLen - 4] */
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* If the count is not a multiple of 4, compute any remaining MACs here.
** No loop unrolling is used. */
k = count % 0x4u;
while(k > 0u)
{
/* Perform the multiply-accumulate */
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* Store the result in the accumulator in the destination buffer. */
*pOut++ = sum;
/* Update the inputA and inputB pointers for next MAC calculation */
py = pIn2 + count;
px = pIn1;
/* Increment the MAC count */
count++;
/* Decrement the loop counter */
blockSize1--;
}
/* --------------------------
* Initializations of stage2
* ------------------------*/
/* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0]
* sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0]
* ....
* sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0]
*/
/* Working pointer of inputA */
px = pIn1;
/* Working pointer of inputB */
pSrc2 = pIn2 + (srcBLen - 1u);
py = pSrc2;
/* count is index by which the pointer pIn1 to be incremented */
count = 0u;
/* -------------------
* Stage2 process
* ------------------*/
/* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed.
* So, to loop unroll over blockSize2,
* srcBLen should be greater than or equal to 4 */
if(srcBLen >= 4u)
{
/* Loop unroll over blockSize2, by 4 */
blkCnt = blockSize2 >> 2u;
while(blkCnt > 0u)
{
/* Set all accumulators to zero */
acc0 = 0.0f;
acc1 = 0.0f;
acc2 = 0.0f;
acc3 = 0.0f;
/* read x[0], x[1], x[2] samples */
x0 = *(px++);
x1 = *(px++);
x2 = *(px++);
/* Apply loop unrolling and compute 4 MACs simultaneously. */
k = srcBLen >> 2u;
/* First part of the processing with loop unrolling. Compute 4 MACs at a time.
** a second loop below computes MACs for the remaining 1 to 3 samples. */
do
{
/* Read y[srcBLen - 1] sample */
c0 = *(py--);
/* Read x[3] sample */
x3 = *(px);
/* Perform the multiply-accumulate */
/* acc0 += x[0] * y[srcBLen - 1] */
acc0 += x0 * c0;
/* acc1 += x[1] * y[srcBLen - 1] */
acc1 += x1 * c0;
/* acc2 += x[2] * y[srcBLen - 1] */
acc2 += x2 * c0;
/* acc3 += x[3] * y[srcBLen - 1] */
acc3 += x3 * c0;
/* Read y[srcBLen - 2] sample */
c0 = *(py--);
/* Read x[4] sample */
x0 = *(px + 1u);
/* Perform the multiply-accumulate */
/* acc0 += x[1] * y[srcBLen - 2] */
acc0 += x1 * c0;
/* acc1 += x[2] * y[srcBLen - 2] */
acc1 += x2 * c0;
/* acc2 += x[3] * y[srcBLen - 2] */
acc2 += x3 * c0;
/* acc3 += x[4] * y[srcBLen - 2] */
acc3 += x0 * c0;
/* Read y[srcBLen - 3] sample */
c0 = *(py--);
/* Read x[5] sample */
x1 = *(px + 2u);
/* Perform the multiply-accumulates */
/* acc0 += x[2] * y[srcBLen - 3] */
acc0 += x2 * c0;
/* acc1 += x[3] * y[srcBLen - 2] */
acc1 += x3 * c0;
/* acc2 += x[4] * y[srcBLen - 2] */
acc2 += x0 * c0;
/* acc3 += x[5] * y[srcBLen - 2] */
acc3 += x1 * c0;
/* Read y[srcBLen - 4] sample */
c0 = *(py--);
/* Read x[6] sample */
x2 = *(px + 3u);
px += 4u;
/* Perform the multiply-accumulates */
/* acc0 += x[3] * y[srcBLen - 4] */
acc0 += x3 * c0;
/* acc1 += x[4] * y[srcBLen - 4] */
acc1 += x0 * c0;
/* acc2 += x[5] * y[srcBLen - 4] */
acc2 += x1 * c0;
/* acc3 += x[6] * y[srcBLen - 4] */
acc3 += x2 * c0;
} while(--k);
/* If the srcBLen is not a multiple of 4, compute any remaining MACs here.
** No loop unrolling is used. */
k = srcBLen % 0x4u;
while(k > 0u)
{
/* Read y[srcBLen - 5] sample */
c0 = *(py--);
/* Read x[7] sample */
x3 = *(px++);
/* Perform the multiply-accumulates */
/* acc0 += x[4] * y[srcBLen - 5] */
acc0 += x0 * c0;
/* acc1 += x[5] * y[srcBLen - 5] */
acc1 += x1 * c0;
/* acc2 += x[6] * y[srcBLen - 5] */
acc2 += x2 * c0;
/* acc3 += x[7] * y[srcBLen - 5] */
acc3 += x3 * c0;
/* Reuse the present samples for the next MAC */
x0 = x1;
x1 = x2;
x2 = x3;
/* Decrement the loop counter */
k--;
}
/* Store the result in the accumulator in the destination buffer. */
*pOut++ = acc0;
*pOut++ = acc1;
*pOut++ = acc2;
*pOut++ = acc3;
/* Increment the pointer pIn1 index, count by 4 */
count += 4u;
/* Update the inputA and inputB pointers for next MAC calculation */
px = pIn1 + count;
py = pSrc2;
/* Decrement the loop counter */
blkCnt--;
}
/* If the blockSize2 is not a multiple of 4, compute any remaining output samples here.
** No loop unrolling is used. */
blkCnt = blockSize2 % 0x4u;
while(blkCnt > 0u)
{
/* Accumulator is made zero for every iteration */
sum = 0.0f;
/* Apply loop unrolling and compute 4 MACs simultaneously. */
k = srcBLen >> 2u;
/* First part of the processing with loop unrolling. Compute 4 MACs at a time.
** a second loop below computes MACs for the remaining 1 to 3 samples. */
while(k > 0u)
{
/* Perform the multiply-accumulates */
sum += *px++ * *py--;
sum += *px++ * *py--;
sum += *px++ * *py--;
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* If the srcBLen is not a multiple of 4, compute any remaining MACs here.
** No loop unrolling is used. */
k = srcBLen % 0x4u;
while(k > 0u)
{
/* Perform the multiply-accumulate */
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* Store the result in the accumulator in the destination buffer. */
*pOut++ = sum;
/* Increment the MAC count */
count++;
/* Update the inputA and inputB pointers for next MAC calculation */
px = pIn1 + count;
py = pSrc2;
/* Decrement the loop counter */
blkCnt--;
}
}
else
{
/* If the srcBLen is not a multiple of 4,
* the blockSize2 loop cannot be unrolled by 4 */
blkCnt = blockSize2;
while(blkCnt > 0u)
{
/* Accumulator is made zero for every iteration */
sum = 0.0f;
/* srcBLen number of MACS should be performed */
k = srcBLen;
while(k > 0u)
{
/* Perform the multiply-accumulate */
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* Store the result in the accumulator in the destination buffer. */
*pOut++ = sum;
/* Increment the MAC count */
count++;
/* Update the inputA and inputB pointers for next MAC calculation */
px = pIn1 + count;
py = pSrc2;
/* Decrement the loop counter */
blkCnt--;
}
}
/* --------------------------
* Initializations of stage3
* -------------------------*/
/* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1]
* sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2]
* ....
* sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2]
* sum += x[srcALen-1] * y[srcBLen-1]
*/
/* In this stage the MAC operations are decreased by 1 for every iteration.
The blockSize3 variable holds the number of MAC operations performed */
/* Working pointer of inputA */
pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u);
px = pSrc1;
/* Working pointer of inputB */
pSrc2 = pIn2 + (srcBLen - 1u);
py = pSrc2;
/* -------------------
* Stage3 process
* ------------------*/
while(blockSize3 > 0u)
{
/* Accumulator is made zero for every iteration */
sum = 0.0f;
/* Apply loop unrolling and compute 4 MACs simultaneously. */
k = blockSize3 >> 2u;
/* First part of the processing with loop unrolling. Compute 4 MACs at a time.
** a second loop below computes MACs for the remaining 1 to 3 samples. */
while(k > 0u)
{
/* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */
sum += *px++ * *py--;
/* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */
sum += *px++ * *py--;
/* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */
sum += *px++ * *py--;
/* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* If the blockSize3 is not a multiple of 4, compute any remaining MACs here.
** No loop unrolling is used. */
k = blockSize3 % 0x4u;
while(k > 0u)
{
/* Perform the multiply-accumulates */
/* sum += x[srcALen-1] * y[srcBLen-1] */
sum += *px++ * *py--;
/* Decrement the loop counter */
k--;
}
/* Store the result in the accumulator in the destination buffer. */
*pOut++ = sum;
/* Update the inputA and inputB pointers for next MAC calculation */
px = ++pSrc1;
py = pSrc2;
/* Decrement the loop counter */
blockSize3--;
}
#else
/* Run the below code for Cortex-M0 */
float32_t *pIn1 = pSrcA; /* inputA pointer */
float32_t *pIn2 = pSrcB; /* inputB pointer */
float32_t sum; /* Accumulator */
uint32_t i, j; /* loop counters */
/* Loop to calculate convolution for output length number of times */
for (i = 0u; i < ((srcALen + srcBLen) - 1u); i++)
{
/* Initialize sum with zero to carry out MAC operations */
sum = 0.0f;
/* Loop to perform MAC operations according to convolution equation */
for (j = 0u; j <= i; j++)
{
/* Check the array limitations */
if((((i - j) < srcBLen) && (j < srcALen)))
{
/* z[i] += x[i-j] * y[j] */
sum += pIn1[j] * pIn2[i - j];
}
}
/* Store the output in the destination buffer */
pDst[i] = sum;
}
#endif /* #ifndef ARM_MATH_CM0_FAMILY */
}
/**
* @} end of Conv group
*/

Wyświetl plik

@ -120,7 +120,7 @@ osMessageQId dacOutputQueueHandle;
uint8_t dacOutputQueueBuffer[ 128 * sizeof( uint8_t ) ];
osStaticMessageQDef_t dacOutputQueueControlBlock;
osMessageQId adcInputQueueHandle;
uint8_t adcInputQueueBuffer[ 3 * sizeof( uint32_t ) ];
uint8_t adcInputQueueBuffer[ 8 * sizeof( uint32_t ) ];
osStaticMessageQDef_t adcInputQueueControlBlock;
/* USER CODE BEGIN PV */

Wyświetl plik

@ -94,7 +94,7 @@ int adjust_input_gain() {
uint16_t vpp, vavg, vmin, vmax;
set_input_gain(gain);
osDelay(100); // Need time for DC offset to settle.
osDelay(1000); // Need time for DC offset to settle.
std::tie(vpp, vavg, vmin, vmax) = readLevels(AUDIO_IN);
INFO("\nVpp = %" PRIu16 ", Vavg = %" PRIu16 "\n", vpp, vavg);
@ -117,7 +117,7 @@ int adjust_input_gain() {
else gain = 0;
set_input_gain(gain);
osDelay(100); // Need time for DC offset to settle.
osDelay(1000); // Need time for DC offset to settle.
std::tie(vpp, vavg, vmin, vmax) = readLevels(AUDIO_IN);
INFO("\nVpp = %" PRIu16 ", Vavg = %" PRIu16 "\n", vpp, vavg);
@ -156,6 +156,8 @@ void setAudioInputLevels()
INFO("Setting input gain: %d", kiss::settings().input_gain);
set_input_gain(kiss::settings().input_gain);
osDelay(1000); // Need time for DC offset to settle.
uint16_t vpp, vavg, vmin, vmax;
std::tie(vpp, vavg, vmin, vmax) = readLevels(AUDIO_IN);

Wyświetl plik

@ -1,205 +1,99 @@
// Copyright 2021 Mobilinkd LLC.
// Copyright 2021-2022 Mobilinkd LLC.
#pragma once
#include "KalmanFilter.h"
#include "Log.h"
#include <algorithm>
#include <array>
#include <cassert>
#include <cstddef>
#include <cstdint>
#include <iterator>
#include <numeric>
namespace mobilinkd { namespace m17 {
/**
* Calculate the phase estimates for each sample position.
*
* This performs a running calculation of the phase of each bit position.
* It is very noisy for individual samples, but quite accurate when
* averaged over an entire M17 frame.
*
* It is designed to be used to calculate the best bit position for each
* frame of data. Samples are collected and averaged. When update() is
* called, the best sample index and clock are estimated, and the counters
* reset for the next frame.
*
* It starts counting bit 0 as the first bit received after a reset.
*
* This is very efficient as it only uses addition and subtraction for
* each bit sample. And uses one multiply and divide per update (per
* frame).
*
* This will permit a clock error of up to 500ppm. This allows up to
* 250ppm error for both transmitter and receiver clocks. This is
* less than one sample per frame when the sample rate is 48000 SPS.
*
* @inv current_index_ is in the interval [0, SAMPLES_PER_SYMBOL).
* @inv sample_index_ is in the interval [0, SAMPLES_PER_SYMBOL).
* @inv clock_ is in the interval [0.9995, 1.0005]
*/
template <typename FloatType, size_t SampleRate, size_t SymbolRate>
class ClockRecovery
template <typename FloatType = float, size_t SamplesPerSymbol = 10>
struct ClockRecovery
{
static constexpr size_t SAMPLES_PER_SYMBOL = SampleRate / SymbolRate;
static constexpr int8_t MAX_OFFSET = SAMPLES_PER_SYMBOL / 2;
static constexpr FloatType dx = 1.0 / SAMPLES_PER_SYMBOL;
static constexpr FloatType MAX_CLOCK = 1.0005;
static constexpr FloatType MIN_CLOCK = 0.9995;
KalmanFilter<FloatType, SamplesPerSymbol> kf_;
size_t count_ = 0;
int8_t sample_index_ = 0;
FloatType clock_estimate_ = 0.;
FloatType sample_estimate_ = 0.;
std::array<FloatType, SAMPLES_PER_SYMBOL> estimates_;
size_t sample_count_ = 0;
uint16_t frame_count_ = 0;
uint8_t sample_index_ = 0;
uint8_t prev_sample_index_ = 0;
uint8_t index_ = 0;
FloatType offset_ = 0.0;
FloatType clock_ = 1.0;
FloatType prev_sample_ = 0.0;
void reset(FloatType z)
{
INFO("CR Reset");
kf_.reset(z);
count_ = 0;
sample_index_ = z;
clock_estimate_ = 0.;
}
void operator()(FloatType)
{
++count_;
}
bool update(uint8_t sw)
{
if (count_ < 8)
{
return false;
}
auto f = kf_.update(sw, count_);
// Constrain sample index to [0..SamplesPerSymbol), wrapping if needed.
sample_estimate_ = f[0];
sample_index_ = int8_t(round(sample_estimate_));
sample_index_ = sample_index_ < 0 ? sample_index_ + SamplesPerSymbol : sample_index_;
sample_index_ = sample_index_ >= int8_t(SamplesPerSymbol) ? sample_index_ - SamplesPerSymbol : sample_index_;
clock_estimate_ = f[1];
count_ = 0;
return true;
}
/**
* Find the sample index.
* This is used when no sync word is found. The sample index is updated
* based on the current clock estimate, the last known good sample
* estimate, and the number of samples processed.
*
* There are @p SAMPLES_PER_INDEX bins. It is expected that half are
* positive values and half are negative. The positive and negative
* bins will be grouped together such that there is a single transition
* from positive values to negative values.
*
* The best bit position is always the position with the positive value
* at that transition point. It will be the bit index with the highest
* energy.
*
* @post sample_index_ contains the best sample point.
* The sample and clock estimates from the filter remain unchanged.
*/
void update_sample_index_()
bool update()
{
uint8_t index = 0;
auto csw = std::fmod((sample_estimate_ + clock_estimate_ * count_), SamplesPerSymbol);
if (csw < 0.) csw += SamplesPerSymbol;
else if (csw >= SamplesPerSymbol) csw -= SamplesPerSymbol;
// Find falling edge.
bool is_positive = false;
for (size_t i = 0; i != SAMPLES_PER_SYMBOL; ++i)
{
FloatType phase = estimates_[i];
// Constrain sample index to [0..SamplesPerSymbol), wrapping if needed.
sample_index_ = int8_t(round(csw));
sample_index_ = sample_index_ < 0 ? sample_index_ + SamplesPerSymbol : sample_index_;
sample_index_ = sample_index_ >= int8_t(SamplesPerSymbol) ? sample_index_ - SamplesPerSymbol : sample_index_;
if (!is_positive && phase > 0)
{
is_positive = true;
}
else if (is_positive && phase < 0)
{
index = i;
break;
}
}
sample_index_ = index == 0 ? SAMPLES_PER_SYMBOL - 1 : index - 1;
}
/**
* Compute the drift in sample points from the last update.
*
* This should never be greater than one.
*/
FloatType calc_offset_()
{
int8_t offset = sample_index_ - prev_sample_index_;
// When in spec, the clock should drift by less than 1 sample per frame.
if (__builtin_expect(offset >= MAX_OFFSET, 0))
{
offset -= SAMPLES_PER_SYMBOL;
}
else if (__builtin_expect(offset <= -MAX_OFFSET, 0))
{
offset += SAMPLES_PER_SYMBOL;
}
return offset;
}
void update_clock_()
{
// update_sample_index_() must be called first.
if (__builtin_expect((frame_count_ == 0), 0))
{
prev_sample_index_ = sample_index_;
offset_ = 0.0;
clock_ = 1.0;
return;
}
offset_ += calc_offset_();
prev_sample_index_ = sample_index_;
clock_ = 1.0 + (offset_ / (frame_count_ * sample_count_));
clock_ = std::min(MAX_CLOCK, std::max(MIN_CLOCK, clock_));
}
public:
ClockRecovery()
{
estimates_.fill(0);
}
/**
* Update clock recovery with the given sample. This will advance the
* current sample index by 1.
*/
void operator()(FloatType sample)
{
FloatType dy = (sample - prev_sample_);
if (sample + prev_sample_ < 0)
{
// Invert the phase estimate when sample midpoint is less than 0.
dy = -dy;
}
prev_sample_ = sample;
estimates_[index_] += dy;
index_ += 1;
if (index_ == SAMPLES_PER_SYMBOL)
{
index_ = 0;
}
sample_count_ += 1;
}
/**
* Reset the state of the clock recovery system. This should be called
* when a new transmission is detected.
*/
void reset()
{
sample_count_ = 0;
frame_count_ = 0;
index_ = 0;
sample_index_ = 0;
estimates_.fill(0);
clock_ = 1.0;
}
/**
* Return the current sample index. This will always be in the range of
* [0..SAMPLES_PER_SYMBOL).
*/
uint8_t current_index() const
{
return index_;
return true;
}
/**
* Return the estimated sample clock increment based on the last update.
*
*
* The value is only valid after samples have been collected and update()
* has been called.
*/
FloatType clock_estimate() const
{
return clock_;
return clock_estimate_;
}
/**
* Return the estimated "best sample index" based on the last update.
*
*
* The value is only valid after samples have been collected and update()
* has been called.
*/
@ -207,35 +101,6 @@ public:
{
return sample_index_;
}
/**
* Update the sample index and clock estimates, and reset the state for
* the next frame of data.
*
* @pre index_ = 0
* @pre sample_count_ > 0
*
* After this is called, sample_index() and clock_estimate() will have
* valid, updated results.
*
* The more samples between calls to update, the more accurate the
* estimates will be.
*
* @return true if the preconditions are met and the update has been
* performed, otherwise false.
*/
bool update()
{
assert(sample_count_ != 0 && index_ == 0);
update_sample_index_();
update_clock_();
frame_count_ = std::min(0x1000, 1 + frame_count_);
sample_count_ = 0;
estimates_.fill(0);
return true;
}
};
}} // mobilinkd::m17

Wyświetl plik

@ -11,6 +11,7 @@
#include <array>
#include <cstdint>
#include <cstddef>
#include <limits>
#include <type_traits>
#include <tuple>

Wyświetl plik

@ -68,7 +68,7 @@ struct DataCarrierDetect
triggered_ = triggered_ ? level_ > ltrigger_ : level_ > htrigger_;
}
void unlock() { triggered_ = false; }
FloatType level() const { return level_; }
bool dcd() const { return triggered_; }
};

Wyświetl plik

@ -36,8 +36,7 @@ struct FirFilter {
FirFilter()
{}
template <size_t N>
FirFilter(std::array<float, N> const& taps)
FirFilter(std::array<float, FILTER_SIZE> const& taps)
{
init(taps);
}
@ -47,8 +46,7 @@ struct FirFilter {
init(taps);
}
template <size_t N>
void init(std::array<float, N> const& taps)
void init(std::array<float, FILTER_SIZE> const& taps)
{
arm_fir_init_f32(&instance, FILTER_SIZE, (float*)taps.data(),
filter_state, BLOCK_SIZE);

Wyświetl plik

@ -1,129 +1,142 @@
// Copyright 2021 Rob Riggs <rob@mobilinkd.com>
// Copyright 2021-2022 Rob Riggs <rob@mobilinkd.com>
// All rights reserved.
#pragma once
#include "IirFilter.hpp"
#include "KalmanFilter.h"
#include "StandardDeviation.hpp"
#include <algorithm>
#include <array>
#include <cmath>
#include <cstddef>
namespace mobilinkd { namespace m17 {
/**
* Deviation and zero-offset estimator.
*
* Accepts samples which are periodically used to update estimates of the
* input signal deviation and zero offset.
*
* Samples must be provided at the ideal sample point (the point with the
* peak bit energy).
*
* Estimates are expected to be updated at each sync word. But they can
* be updated more frequently, such as during the preamble.
*/
template <typename FloatType>
template <typename FloatType, size_t SYNC_WORD_LEN = 8>
class FreqDevEstimator
{
using sample_filter_t = tnc::IirFilter<3>;
static constexpr FloatType DEVIATION = 1.;
// IIR with Nyquist of 1/4.
static constexpr std::array<float, 3> dc_b = { 0.09763107, 0.19526215, 0.09763107 };
static constexpr std::array<float, 3> dc_a = { 1. , -0.94280904, 0.33333333 };
static constexpr FloatType MAX_DC_ERROR = 0.2;
FloatType min_est_ = 0.0;
FloatType max_est_ = 0.0;
FloatType min_cutoff_ = 0.0;
FloatType max_cutoff_ = 0.0;
FloatType min_var_ = 0.0;
FloatType max_var_ = 0.0;
size_t min_count_ = 1;
size_t max_count_ = 1;
FloatType deviation_ = 0.0;
FloatType offset_ = 0.0;
FloatType error_ = 0.0;
FloatType idev_ = 1.0;
sample_filter_t dc_filter_{dc_b, dc_a};
SymbolKalmanFilter<FloatType> minFilter_;
SymbolKalmanFilter<FloatType> maxFilter_;
RunningStandardDeviation<FloatType, 184> stddev_;
FloatType idev_ = 1.;
FloatType offset_ = 0.;
uint8_t count_ = 0;
FloatType min_ = 0.;
FloatType max_ = 0.;
uint8_t minCount_ = 0;
uint8_t maxCount_ = 0;
size_t updateCount_ = 0;
bool reset_ = true;
public:
void reset()
{
min_est_ = 0.0;
max_est_ = 0.0;
min_var_ = 0.0;
max_var_ = 0.0;
min_count_ = 1;
max_count_ = 1;
min_cutoff_ = 0.0;
max_cutoff_ = 0.0;
}
void reset()
{
idev_ = 1.;
offset_ = 0.;
count_ = 0;
min_ = 0.;
max_ = 0.;
minCount_ = 0;
maxCount_ = 0;
updateCount_ = 0;
stddev_.reset();
reset_ = true;
}
void sample(FloatType sample)
{
if (sample < 1.5 * min_est_)
{
min_count_ = 1;
min_est_ = sample;
min_var_ = 0.0;
min_cutoff_ = min_est_ * 0.666666;
}
else if (sample < min_cutoff_)
{
min_count_ += 1;
min_est_ += sample;
FloatType var = (min_est_ / min_count_) - sample;
min_var_ += var * var;
}
else if (sample > 1.5 * max_est_)
{
max_count_ = 1;
max_est_ = sample;
max_var_ = 0.0;
max_cutoff_ = max_est_ * 0.666666;
}
else if (sample > max_cutoff_)
{
max_count_ += 1;
max_est_ += sample;
FloatType var = (max_est_ / max_count_) - sample;
max_var_ += var * var;
}
}
/**
* This function takes the index samples from the correlator to build
* the outer symbol samples for the frequency offset (signal DC offset)
* and the deviation (signal magnitude). It expects bursts of 8 samples,
* one for each symbol in a sync word.
*
* @param sample
*/
void sample(FloatType sample)
{
count_ += 1;
/**
* Update the estimates for deviation, offset, and EVM (error). Note
* that the estimates for error are using a sloppy implementation for
* calculating variance to reduce the memory requirements. This is
* because this is designed for embedded use.
*/
void update()
{
if (max_count_ < 2 || min_count_ < 2) return;
FloatType max_ = max_est_ / max_count_;
FloatType min_ = min_est_ / min_count_;
deviation_ = (max_ - min_) / 6.0;
if (deviation_ > 0) idev_ = 1.0 / deviation_;
offset_ = dc_filter_(std::max(std::min(max_ + min_, deviation_ * MAX_DC_ERROR), deviation_ * -MAX_DC_ERROR));
error_ = (std::sqrt(max_var_ / (max_count_ - 1)) + std::sqrt(min_var_ / (min_count_ - 1))) * 0.5 * idev_;
min_cutoff_ = offset_ - deviation_ * 2;
max_cutoff_ = offset_ + deviation_ * 2;
max_est_ = max_;
min_est_ = min_;
max_count_ = 1;
min_count_ = 1;
max_var_ = 0.0;
min_var_ = 0.0;
}
if (sample < 0)
{
minCount_ += 1;
min_ += sample;
}
else
{
maxCount_ += 1;
max_ += sample;
}
FloatType deviation() const { return deviation_; }
FloatType offset() const { return offset_; }
FloatType error() const { return error_; }
FloatType idev() const { return idev_; }
if (count_ == SYNC_WORD_LEN)
{
auto minAvg = min_ / minCount_;
auto maxAvg = max_ / maxCount_;
if (reset_)
{
minFilter_.reset(minAvg);
maxFilter_.reset(maxAvg);
idev_ = 6.0 / (maxAvg - minAvg);
offset_ = maxAvg + minAvg;
reset_ = false;
}
else
{
auto minFiltered = minFilter_.update(minAvg, count_ + updateCount_);
auto maxFiltered = maxFilter_.update(maxAvg, count_ + updateCount_);
idev_ = 6.0 / (maxFiltered[0] - minFiltered[0]);
offset_ = maxFiltered[0] + minFiltered[0];
}
count_ = 0;
updateCount_ = 0;
min_ = 0.;
max_ = 0.;
minCount_ = 0;
maxCount_ = 0;
}
}
FloatType normalize(FloatType sample) const
{
return (sample - offset_) * idev_;
}
FloatType evm() const { return stddev_.stdev(); }
void update() const {}
/**
* Capture EVM of a symbol.
*
* @param sample is a normalized sample captured at the best sample point.
*/
void update(FloatType sample)
{
if (sample > 2)
{
stddev_.capture(sample - 3);
}
else if (sample > 0)
{
stddev_.capture(sample - 1);
}
else if (sample > -2)
{
stddev_.capture(sample + 1);
}
else
{
stddev_.capture(sample + 3);
}
updateCount_ += 1;
}
FloatType idev() const { return idev_; }
FloatType offset() const { return offset_; }
FloatType deviation() const { return DEVIATION / idev_; }
FloatType error() const { return evm(); }
};
}} // mobilinkd::m17

Wyświetl plik

@ -28,6 +28,8 @@ struct IirFilter {
static constexpr size_t size() { return N; }
void reset() { history_.fill(0.0f); }
float operator()(float input)
{

125
TNC/KalmanFilter.h 100644
Wyświetl plik

@ -0,0 +1,125 @@
// Copyright 2022 Mobilinkd LLC.
#pragma once
#include "Log.h"
#define BLAZE_THROW( EXCEPTION ) \
ERROR(#EXCEPTION); \
abort()
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
#include <blaze/math/Matrix.h>
#include <blaze/math/Vector.h>
// STM32 headers define RNG, and this conflicts with Blaze.
#if defined(RNG)
#define RNG_SAVED_VALUE__ RNG
#undef RNG
#include <blaze/Math.h>
#define RNG RNG_SAVED_VALUE__
#undef RNG_SAVED_VALUE__
#else
#include <blaze/Math.h>
#endif
#pragma GCC diagnostic pop
#include <cmath>
namespace mobilinkd { namespace m17 {
template <typename FloatType, size_t SamplesPerSymbol>
struct KalmanFilter
{
blaze::StaticVector<FloatType, 2> x;
blaze::StaticMatrix<FloatType, 2, 2> P;
blaze::StaticMatrix<FloatType, 2, 2> F;
blaze::StaticMatrix<FloatType, 1, 2> H = {{1., 0.}};
blaze::StaticMatrix<FloatType, 1, 1> R = {{0.5}};
blaze::StaticMatrix<FloatType, 2, 2> Q = {{6.25e-13, 1.25e-12},{1.25e-12, 2.50e-12}};
KalmanFilter()
{
reset(0.);
}
void reset(FloatType z)
{
x = {z, 0.};
P = {{4., 0.}, {0., 0.00000025}};
F = {{1., 1.}, {0., 1.}};
}
[[gnu::noinline]]
auto update(FloatType z, size_t dt)
{
F(0,1) = FloatType(dt);
x = F * x;
P = F * P * blaze::trans(F) + Q;
auto S = H * P * blaze::trans(H) + R;
auto K = P * blaze::trans(H) * (1.0 / S(0, 0));
// Normalize incoming index
if (z - x[0] < (SamplesPerSymbol / -2.0)) // wrapped forwards 9 -> 0
z += SamplesPerSymbol;
else if (z - x[0] > (SamplesPerSymbol / 2.0)) // wrapped 0 -> 9
z -= SamplesPerSymbol;
auto y = z - H * x;
x += K * y;
// Normalize the filtered sample point
while (x[0] >= SamplesPerSymbol) x[0] -= SamplesPerSymbol;
while (x[0] < 0) x[0] += SamplesPerSymbol;
P = P - K * H * P;
return x;
}
};
template <typename FloatType>
struct SymbolKalmanFilter
{
blaze::StaticVector<FloatType, 2> x;
blaze::StaticMatrix<FloatType, 2, 2> P;
blaze::StaticMatrix<FloatType, 2, 2> F;
blaze::StaticMatrix<FloatType, 1, 2> H = {{1., 0.}};
blaze::StaticMatrix<FloatType, 1, 1> R = {{0.5}};
blaze::StaticMatrix<FloatType, 2, 2> Q = {{6.25e-4, 1.25e-3},{1.25e-3, 2.50e-3}};
SymbolKalmanFilter()
{
reset(0.);
}
void reset(FloatType z)
{
x = {z, 0.};
P = {{4., 0.}, {0., 0.00000025}};
F = {{1., 1.}, {0., 1.}};
}
[[gnu::noinline]]
auto update(FloatType z, size_t dt)
{
F(0,1) = FloatType(dt);
x = F * x;
P = F * P * blaze::trans(F) + Q;
auto S = H * P * blaze::trans(H) + R;
auto K = P * blaze::trans(H) * (1.0 / S(0, 0));
auto y = z - H * x;
x += K * y;
// Normalize the filtered sample point
P = P - K * H * P;
return x;
}
};
}} // mobilinkd::m17

Wyświetl plik

@ -1,4 +1,4 @@
// Copyright 2018-2021 Rob Riggs <rob@mobilinkd.com>
// Copyright 2018-2022 Rob Riggs <rob@mobilinkd.com>
// All rights reserved.
#include "KissHardware.hpp"
@ -43,13 +43,13 @@ int powerOffViaUSB(void)
namespace mobilinkd { namespace tnc { namespace kiss {
#if defined(NUCLEOTNC)
const char FIRMWARE_VERSION[] = "2.4.1";
const char FIRMWARE_VERSION[] = "2.4.4";
const char HARDWARE_VERSION[] = "Mobilinkd NucleoTNC";
#elif defined(STM32L433xx)
const char FIRMWARE_VERSION[] = "2.4.1";
const char FIRMWARE_VERSION[] = "2.4.4";
const char HARDWARE_VERSION[] = "Mobilinkd TNC3 2.1.1";
#elif defined(STM32L4P5xx)
const char FIRMWARE_VERSION[] = "2.4.1";
const char FIRMWARE_VERSION[] = "2.4.4";
const char HARDWARE_VERSION[] = "Mobilinkd TNC3+ Rev A";
#endif
Hardware& settings()

Wyświetl plik

@ -84,10 +84,18 @@ const std::array<int16_t, FILTER_TAP_NUM_21> rrc_taps_21 = {
3, 1, -1, 0
};
const std::array<float, FILTER_TAP_NUM> rrc_taps_f = {
-0.009265784007800534, -0.006136551625729697, -0.001125978562075172, 0.004891777252042491, 0.01071805138282269, 0.01505751553351295, 0.01679337935001369, 0.015256245142156299, 0.01042830577908502, 0.003031522725559901, -0.0055333532968188165, -0.013403099825723372, -0.018598682349642525, -0.01944761739590459, -0.015005271935951746, -0.0053887880354343935, 0.008056525910253532, 0.022816244158307273, 0.035513467692208076, 0.04244131815783876, 0.04025481153629372, 0.02671818654865632, 0.0013810216516704976, -0.03394615682795165, -0.07502635967975885, -0.11540977897637611, -0.14703962203941534, -0.16119995609538576, -0.14969512896336504, -0.10610329539459686, -0.026921412469634916, 0.08757875030779196, 0.23293327870303457, 0.4006012210123992, 0.5786324696325503, 0.7528286479934068, 0.908262741447522, 1.0309661131633199, 1.1095611856548013, 1.1366197723675815, 1.1095611856548013, 1.0309661131633199, 0.908262741447522, 0.7528286479934068, 0.5786324696325503, 0.4006012210123992, 0.23293327870303457, 0.08757875030779196, -0.026921412469634916, -0.10610329539459686, -0.14969512896336504, -0.16119995609538576, -0.14703962203941534, -0.11540977897637611, -0.07502635967975885, -0.03394615682795165, 0.0013810216516704976, 0.02671818654865632, 0.04025481153629372, 0.04244131815783876, 0.035513467692208076, 0.022816244158307273, 0.008056525910253532, -0.0053887880354343935, -0.015005271935951746, -0.01944761739590459, -0.018598682349642525, -0.013403099825723372, -0.0055333532968188165, 0.003031522725559901, 0.01042830577908502, 0.015256245142156299, 0.01679337935001369, 0.01505751553351295, 0.01071805138282269, 0.004891777252042491, -0.001125978562075172, -0.006136551625729697, -0.009265784007800534, 0.0
};
const std::array<float, FILTER_TAP_NUM_9> rrc_taps_f9 = {
0.002017321931508163, -0.0018256054303579805, -0.00571615173291049, -0.008746639552588416, -0.010105075751866371, -0.009265784007800534, -0.006136551625729697, -0.001125978562075172, 0.004891777252042491, 0.01071805138282269, 0.01505751553351295, 0.01679337935001369, 0.015256245142156299, 0.01042830577908502, 0.003031522725559901, -0.0055333532968188165, -0.013403099825723372, -0.018598682349642525, -0.01944761739590459, -0.015005271935951746, -0.0053887880354343935, 0.008056525910253532, 0.022816244158307273, 0.035513467692208076, 0.04244131815783876, 0.04025481153629372, 0.02671818654865632, 0.0013810216516704976, -0.03394615682795165, -0.07502635967975885, -0.11540977897637611, -0.14703962203941534, -0.16119995609538576, -0.14969512896336504, -0.10610329539459686, -0.026921412469634916, 0.08757875030779196, 0.23293327870303457, 0.4006012210123992, 0.5786324696325503, 0.7528286479934068, 0.908262741447522, 1.0309661131633199, 1.1095611856548013, 1.1366197723675815, 1.1095611856548013, 1.0309661131633199, 0.908262741447522, 0.7528286479934068, 0.5786324696325503, 0.4006012210123992, 0.23293327870303457, 0.08757875030779196, -0.026921412469634916, -0.10610329539459686, -0.14969512896336504, -0.16119995609538576, -0.14703962203941534, -0.11540977897637611, -0.07502635967975885, -0.03394615682795165, 0.0013810216516704976, 0.02671818654865632, 0.04025481153629372, 0.04244131815783876, 0.035513467692208076, 0.022816244158307273, 0.008056525910253532, -0.0053887880354343935, -0.015005271935951746, -0.01944761739590459, -0.018598682349642525, -0.013403099825723372, -0.0055333532968188165, 0.003031522725559901, 0.01042830577908502, 0.015256245142156299, 0.01679337935001369, 0.01505751553351295, 0.01071805138282269, 0.004891777252042491, -0.001125978562075172, -0.006136551625729697, -0.009265784007800534, -0.010105075751866371, -0.008746639552588416, -0.00571615173291049, -0.0018256054303579805, 0.002017321931508163, 0.0
};
const std::array<float, FILTER_TAP_NUM_11> rrc_taps_f11 = {
-0.005648131453822014, -0.006126925416243605, -0.005349511529163396, -0.003403189203405097, -0.0006430502751187517, 0.002365929161655135, 0.004957956568090113, 0.006506845894531803, 0.006569574194782443, 0.0050017573119839134, 0.002017321931508163, -0.0018256054303579805, -0.00571615173291049, -0.008746639552588416, -0.010105075751866371, -0.009265784007800534, -0.006136551625729697, -0.001125978562075172, 0.004891777252042491, 0.01071805138282269, 0.01505751553351295, 0.01679337935001369, 0.015256245142156299, 0.01042830577908502, 0.003031522725559901, -0.0055333532968188165, -0.013403099825723372, -0.018598682349642525, -0.01944761739590459, -0.015005271935951746, -0.0053887880354343935, 0.008056525910253532, 0.022816244158307273, 0.035513467692208076, 0.04244131815783876, 0.04025481153629372, 0.02671818654865632, 0.0013810216516704976, -0.03394615682795165, -0.07502635967975885, -0.11540977897637611, -0.14703962203941534, -0.16119995609538576, -0.14969512896336504, -0.10610329539459686, -0.026921412469634916, 0.08757875030779196, 0.23293327870303457, 0.4006012210123992, 0.5786324696325503, 0.7528286479934068, 0.908262741447522, 1.0309661131633199, 1.1095611856548013, 1.1366197723675815, 1.1095611856548013, 1.0309661131633199, 0.908262741447522, 0.7528286479934068, 0.5786324696325503, 0.4006012210123992, 0.23293327870303457, 0.08757875030779196, -0.026921412469634916, -0.10610329539459686, -0.14969512896336504, -0.16119995609538576, -0.14703962203941534, -0.11540977897637611, -0.07502635967975885, -0.03394615682795165, 0.0013810216516704976, 0.02671818654865632, 0.04025481153629372, 0.04244131815783876, 0.035513467692208076, 0.022816244158307273, 0.008056525910253532, -0.0053887880354343935, -0.015005271935951746, -0.01944761739590459, -0.018598682349642525, -0.013403099825723372, -0.0055333532968188165, 0.003031522725559901, 0.01042830577908502, 0.015256245142156299, 0.01679337935001369, 0.01505751553351295, 0.01071805138282269, 0.004891777252042491, -0.001125978562075172, -0.006136551625729697, -0.009265784007800534, -0.010105075751866371, -0.008746639552588416, -0.00571615173291049, -0.0018256054303579805, 0.002017321931508163, 0.0050017573119839134, 0.006569574194782443, 0.006506845894531803, 0.004957956568090113, 0.002365929161655135, -0.0006430502751187517, -0.003403189203405097, -0.005349511529163396, -0.006126925416243605, -0.005648131453822014, 0.0
};
const std::array<float, FILTER_TAP_NUM_15> rrc_taps_f15 = {
0.0029364388513841593, 0.0031468394550958484, 0.002699564567597445, 0.001661182944400927, 0.00023319405581230247, -0.0012851320781224025, -0.0025577136087664687, -0.0032843366522956313, -0.0032697038088887226, -0.0024733964729590865, -0.0010285696910973807, 0.0007766690889758685, 0.002553421969211845, 0.0038920145144327816, 0.004451886520053017, 0.00404219185231544, 0.002674727068399207, 0.0005756567993179152, -0.0018493784971116507, -0.004092346891623224, -0.005648131453822014, -0.006126925416243605, -0.005349511529163396, -0.003403189203405097, -0.0006430502751187517, 0.002365929161655135, 0.004957956568090113, 0.006506845894531803, 0.006569574194782443, 0.0050017573119839134, 0.002017321931508163, -0.0018256054303579805, -0.00571615173291049, -0.008746639552588416, -0.010105075751866371, -0.009265784007800534, -0.006136551625729697, -0.001125978562075172, 0.004891777252042491, 0.01071805138282269, 0.01505751553351295, 0.01679337935001369, 0.015256245142156299, 0.01042830577908502, 0.003031522725559901, -0.0055333532968188165, -0.013403099825723372, -0.018598682349642525, -0.01944761739590459, -0.015005271935951746, -0.0053887880354343935, 0.008056525910253532, 0.022816244158307273, 0.035513467692208076, 0.04244131815783876, 0.04025481153629372, 0.02671818654865632, 0.0013810216516704976, -0.03394615682795165, -0.07502635967975885, -0.11540977897637611, -0.14703962203941534, -0.16119995609538576, -0.14969512896336504, -0.10610329539459686, -0.026921412469634916, 0.08757875030779196, 0.23293327870303457, 0.4006012210123992, 0.5786324696325503, 0.7528286479934068, 0.908262741447522, 1.0309661131633199, 1.1095611856548013, 1.1366197723675815, 1.1095611856548013, 1.0309661131633199, 0.908262741447522, 0.7528286479934068, 0.5786324696325503, 0.4006012210123992, 0.23293327870303457, 0.08757875030779196, -0.026921412469634916, -0.10610329539459686, -0.14969512896336504, -0.16119995609538576, -0.14703962203941534, -0.11540977897637611, -0.07502635967975885, -0.03394615682795165, 0.0013810216516704976, 0.02671818654865632, 0.04025481153629372, 0.04244131815783876, 0.035513467692208076, 0.022816244158307273, 0.008056525910253532, -0.0053887880354343935, -0.015005271935951746, -0.01944761739590459, -0.018598682349642525, -0.013403099825723372, -0.0055333532968188165, 0.003031522725559901, 0.01042830577908502, 0.015256245142156299, 0.01679337935001369, 0.01505751553351295, 0.01071805138282269, 0.004891777252042491, -0.001125978562075172, -0.006136551625729697, -0.009265784007800534, -0.010105075751866371, -0.008746639552588416, -0.00571615173291049, -0.0018256054303579805, 0.002017321931508163, 0.0050017573119839134, 0.006569574194782443, 0.006506845894531803, 0.004957956568090113, 0.002365929161655135, -0.0006430502751187517, -0.003403189203405097, -0.005349511529163396, -0.006126925416243605, -0.005648131453822014, -0.004092346891623224, -0.0018493784971116507, 0.0005756567993179152, 0.002674727068399207, 0.00404219185231544, 0.004451886520053017, 0.0038920145144327816, 0.002553421969211845, 0.0007766690889758685, -0.0010285696910973807, -0.0024733964729590865, -0.0032697038088887226, -0.0032843366522956313, -0.0025577136087664687, -0.0012851320781224025, 0.00023319405581230247, 0.001661182944400927, 0.002699564567597445, 0.0031468394550958484, 0.0029364388513841593, 0.0
};

Wyświetl plik

@ -21,7 +21,9 @@ extern const std::array<int16_t, FILTER_TAP_NUM_11> rrc_taps_11;
extern const std::array<int16_t, FILTER_TAP_NUM_15> rrc_taps_15;
extern const std::array<int16_t, FILTER_TAP_NUM_21> rrc_taps_21;
extern const std::array<float, FILTER_TAP_NUM> rrc_taps_f;
extern const std::array<float, FILTER_TAP_NUM_9> rrc_taps_f9;
extern const std::array<float, FILTER_TAP_NUM_11> rrc_taps_f11;
extern const std::array<float, FILTER_TAP_NUM_15> rrc_taps_f15;
constexpr std::array<uint8_t, 2> LSF_SYNC = { 0x55, 0xF7 };

Wyświetl plik

@ -1,6 +1,9 @@
// Copyright 2020-2021 Rob Riggs <rob@mobilinkd.com>
// Copyright 2020-2022 Rob Riggs <rob@mobilinkd.com>
// All rights reserved.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wvolatile"
#include "AudioLevel.hpp"
#include "M17Demodulator.h"
#include "Util.h"
@ -8,6 +11,7 @@
#include "main.h"
#include "stm32l4xx_hal.h"
#pragma GCC diagnostic pop
#include <algorithm>
#include <array>
@ -19,19 +23,35 @@ namespace mobilinkd { namespace tnc {
//m17::Indicator dcd_indicator{GPIOA, GPIO_PIN_2};
//m17::Indicator str_indicator{GPIOA, GPIO_PIN_7};
static float scale = 1.f / 2560.f;
static float scale = 1.f / 32768.f;
static float dc_block(float x)
{
#if 1
return x;
#else
static float xm1 = 0.0;
static float ym1 = 0.0;
float y = x - xm1 + 0.9999 * ym1;
xm1 = x;
ym1 = y;
return y;
#endif
}
void M17Demodulator::start()
{
SysClock72();
SysClock48();
#if defined(HAVE_LSCO)
HAL_RCCEx_DisableLSCO();
#endif
demod_filter.init(m17::rrc_taps_f15);
demod_filter.init(m17::rrc_taps_f);
passall(kiss::settings().options & KISS_OPTION_PASSALL);
polarity = kiss::settings().rx_rev_polarity() ? -1 : 1;
scale = 1.f / 2560.f * polarity;
scale = 1.f / 32768.f * polarity;
audio::virtual_ground = (VREF + 1) / 2;
hadc1.Init.OversamplingMode = ENABLE;
@ -51,41 +71,56 @@ void M17Demodulator::start()
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
CxxErrorHandler();
startADC(1499, ADC_BLOCK_SIZE);
startADC(999, ADC_BLOCK_SIZE);
// getModulator().start_loopback();
dcd_off();
}
/**
* Update the deviation & offset from the stored correlator samples. This is
* called after a sync word has been detected.
*
* @pre @p sample_index is the best estimate of the sample point and has
* been set, either by the clock recovery system or from a sync word if
* the demodulator was in an unlocked state.
*
* @post @p dev has been updated with the latest sync word samples. And
* @p sync_sample_index is set to the current sync word tigger point.
*
* @param index is the current sync word trigger point.
*/
void M17Demodulator::update_values(uint8_t index)
{
correlator.apply([this,index](float t){dev.sample(t);}, index);
// For deviation and offset to be accurate, this must be the stable
// sample_index. The sync word trigger point is too noisy, resulting
// in inaccurate frequency offset and deviation estimates.
correlator.apply([this,index](float t){dev.sample(t);}, sample_index);
dev.update();
idev = dev.idev();
sync_sample_index = index;
}
void M17Demodulator::dcd_on()
{
// Data carrier newly detected.
INFO("dcd = %d", int(dcd.level() * 100));
INFO("dcd = %d", int(dcd.level() * 1000));
dcd_ = true;
sync_count = 0;
dev.reset();
framer.reset();
decoder.reset();
missing_sync_count = 0;
// dcd_indicator.off();
if (demodState == DemodState::UNLOCKED)
{
sync_count = 0;
missing_sync_count = 0;
dev.reset();
framer.reset();
decoder.reset();
}
}
void M17Demodulator::dcd_off()
{
// Just lost data carrier.
INFO("dcd = %d", int(dcd.level() * 100));
dcd_ = false;
INFO("dcd = %d", int(dcd.level() * 1000));
demodState = DemodState::UNLOCKED;
// dcd_indicator.on();
adc_timing_adjust = 0;
prev_clock_estimate = 1.;
dcd_ = false;
}
void M17Demodulator::initialize(const q15_t* input)
@ -97,14 +132,14 @@ void M17Demodulator::initialize(const q15_t* input)
auto filtered = demod_filter(demod_buffer.data());
for (size_t i = 0; i != ADC_BLOCK_SIZE; ++i)
{
auto filtered_sample = filtered[i];
auto filtered_sample = dc_block(filtered[i]);
correlator.sample(filtered_sample);
}
}
void M17Demodulator::update_dcd(const q15_t* input)
{
static constexpr float inv = 1.0 / 2048.0;
static constexpr float inv = 1.0 / 16384.0;
if (!dcd_ && dcd.dcd())
{
@ -137,8 +172,8 @@ void M17Demodulator::do_unlocked()
missing_sync_count = 0;
need_clock_reset_ = true;
dev.reset();
update_values(sync_index);
sample_index = sync_index;
update_values(sync_index);
demodState = DemodState::LSF_SYNC;
INFO("P sync %d", sync_index);
}
@ -149,12 +184,12 @@ void M17Demodulator::do_unlocked()
auto sync_updated = lsf_sync.updated();
if (sync_updated)
{
sync_count = 0;
sync_count = MAX_SYNC_COUNT;
missing_sync_count = 0;
need_clock_reset_ = true;
dev.reset();
update_values(sync_index);
sample_index = sync_index;
update_values(sync_index);
demodState = DemodState::FRAME;
if (sync_updated < 0)
{
@ -171,12 +206,12 @@ void M17Demodulator::do_unlocked()
sync_updated = packet_sync.updated();
if (sync_updated < 0)
{
sync_count = 0;
sync_count = MAX_SYNC_COUNT;
missing_sync_count = 0;
need_clock_reset_ = true;
dev.reset();
update_values(sync_index);
sample_index = sync_index;
update_values(sync_index);
demodState = DemodState::FRAME;
sync_word_type = M17FrameDecoder::SyncWordType::BERT;
INFO("B sync %d", int(sync_index));
@ -200,7 +235,8 @@ void M17Demodulator::do_lsf_sync()
// INFO("PSync = %d", int(sync_triggered));
if (sync_triggered > 0.1)
{
ITM_SendChar('.');
need_clock_update_ = true;
sync_count += 1;
return;
}
sync_triggered = lsf_sync.triggered(correlator);
@ -208,6 +244,7 @@ void M17Demodulator::do_lsf_sync()
if (bert_triggered < 0)
{
missing_sync_count = 0;
sync_count = MAX_SYNC_COUNT;
need_clock_update_ = true;
update_values(sample_index);
demodState = DemodState::FRAME;
@ -217,6 +254,7 @@ void M17Demodulator::do_lsf_sync()
else if (std::abs(sync_triggered) > 0.1)
{
missing_sync_count = 0;
sync_count = MAX_SYNC_COUNT;
need_clock_update_ = true;
update_values(sample_index);
INFO("LSync = %d", int(sync_triggered));
@ -235,9 +273,19 @@ void M17Demodulator::do_lsf_sync()
}
else if (++missing_sync_count > 192)
{
demodState = DemodState::UNLOCKED;
INFO("l unlock %d", int(missing_sync_count));
missing_sync_count = 0;
if (sync_count >= 10) {
// Long preamble. Update clock and continue waiting for LSF.
missing_sync_count = 0;
need_clock_update_ = true;
INFO("long preamble");
} else {
// No sync word. Recycle.
sync_count = 0;
demodState = DemodState::UNLOCKED;
missing_sync_count = 0;
dcd.unlock();
INFO("l unlock %d", int(missing_sync_count));
}
}
else
{
@ -255,36 +303,70 @@ void M17Demodulator::do_lsf_sync()
[[gnu::noinline]]
void M17Demodulator::do_stream_sync()
{
static bool eot_flag = false;
sync_count += 1;
if (sync_count < MIN_SYNC_COUNT) {
return;
}
if (eot_sync.triggered(correlator) > EOT_TRIGGER_LEVEL) {
// Note the EOT flag but continue trying to decode. This is needed
// to avoid false triggers. If it is a true EOT, the stream will
// end the next time we try to capture a sync word.
sync_word_type = M17FrameDecoder::SyncWordType::STREAM;
demodState = DemodState::FRAME;
eot_flag = true;
missing_sync_count = 0;
INFO("EOT");
return;
}
uint8_t sync_index = lsf_sync(correlator);
int8_t sync_updated = lsf_sync.updated();
sync_count += 1;
if (sync_updated < 0)
{
missing_sync_count = 0;
if (sync_count > 70)
update_values(sync_index);
sync_word_type = M17FrameDecoder::SyncWordType::STREAM;
demodState = DemodState::SYNC_WAIT;
INFO("s sync %d", int(sync_count));
eot_flag = false;
}
else if (sync_count > MAX_SYNC_COUNT)
{
if (ber >= 0 && ber < STREAM_COST_LIMIT)
{
update_values(sync_index);
// Sync word missed but we are still decoding a stream reasonably
// well. Don't increment the missing sync count, but it must not
// be 0 when a sync word is missed for clock recovery to work.
if (!missing_sync_count) missing_sync_count = 1;
sync_word_type = M17FrameDecoder::SyncWordType::STREAM;
demodState = DemodState::FRAME;
INFO("s sync %d", int(sync_index));
INFO("s bunsync");
}
return;
}
else if (sync_count > 87)
{
update_values(sync_index);
missing_sync_count += 1;
if (missing_sync_count < MAX_MISSING_SYNC)
else if (eot_flag) {
// EOT flag set, missing sync, and very high BER. Stream has ended.
demodState = DemodState::UNLOCKED;
dcd.unlock();
INFO("s eot");
}
else if (missing_sync_count < MAX_MISSING_SYNC)
{
// Sync word missed, very high error rate. Still trying to decode.
missing_sync_count += 1;
sync_word_type = M17FrameDecoder::SyncWordType::STREAM;
demodState = DemodState::FRAME;
INFO("s unsync %d", int(missing_sync_count));
}
else
{
demodState = DemodState::LSF_SYNC;
// No EOT, but too many sync words missed. Recycle.
demodState = DemodState::UNLOCKED;
dcd.unlock();
INFO("s unlock");
}
eot_flag = false;
}
}
@ -295,30 +377,46 @@ void M17Demodulator::do_stream_sync()
[[gnu::noinline]]
void M17Demodulator::do_packet_sync()
{
sync_count += 1;
if (sync_count < MIN_SYNC_COUNT) {
return;
}
auto sync_index = packet_sync(correlator);
auto sync_updated = packet_sync.updated();
sync_count += 1;
if (sync_count > 70 && sync_updated)
if (sync_updated)
{
missing_sync_count = 0;
update_values(sync_index);
sync_word_type = M17FrameDecoder::SyncWordType::PACKET;
demodState = DemodState::FRAME;
demodState = DemodState::SYNC_WAIT;
INFO("k sync");
return;
}
else if (sync_count > 87)
else if (sync_count > MAX_SYNC_COUNT)
{
missing_sync_count += 1;
if (missing_sync_count < MAX_MISSING_SYNC)
if (ber >= 0 && ber < PACKET_COST_LIMIT)
{
// Sync word missed but we are still decoding reasonably well.
if (!missing_sync_count) missing_sync_count = 1;
sync_word_type = M17FrameDecoder::SyncWordType::PACKET;
demodState = DemodState::FRAME;
INFO("k bunsync");
}
else if (missing_sync_count < MAX_MISSING_SYNC)
{
// Sync word missed, very high error rate. Still trying to decode.
// This may not be appropriate for packet mode.
missing_sync_count += 1;
sync_word_type = M17FrameDecoder::SyncWordType::PACKET;
demodState = DemodState::FRAME;
INFO("k unsync");
}
else
{
// Too many sync words missed. Recycle.
demodState = DemodState::UNLOCKED;
dcd.unlock();
INFO("k unlock");
}
}
@ -330,22 +428,35 @@ void M17Demodulator::do_packet_sync()
[[gnu::noinline]]
void M17Demodulator::do_bert_sync()
{
sync_count += 1;
if (sync_count < MIN_SYNC_COUNT) {
return;
}
auto sync_index = packet_sync(correlator);
auto sync_updated = packet_sync.updated();
sync_count += 1;
if (sync_count > 70 && sync_updated < 0)
if (sync_updated < 0)
{
missing_sync_count = 0;
update_values(sync_index);
sync_word_type = M17FrameDecoder::SyncWordType::BERT;
INFO("b sync");
demodState = DemodState::FRAME;
demodState = DemodState::SYNC_WAIT;
}
else if (sync_count > 87)
else if (sync_count > MAX_SYNC_COUNT)
{
missing_sync_count += 1;
if (missing_sync_count < MAX_MISSING_SYNC)
if (ber >= 0 && ber < STREAM_COST_LIMIT)
{
// Sync word missed but we are still decoding a stream reasonably well.
if (!missing_sync_count) missing_sync_count = 1;
sync_word_type = M17FrameDecoder::SyncWordType::BERT;
demodState = DemodState::FRAME;
INFO("b bunsync");
}
else if (missing_sync_count < MAX_MISSING_SYNC)
{
missing_sync_count += 1;
sync_word_type = M17FrameDecoder::SyncWordType::BERT;
demodState = DemodState::FRAME;
INFO("b unsync");
@ -353,33 +464,63 @@ void M17Demodulator::do_bert_sync()
else
{
demodState = DemodState::UNLOCKED;
dcd.unlock();
INFO("b unlock");
}
}
}
/**
* Wait for the sync_count to hit MAX_SYNC_COUNT. This is necessary for
* proper timing. Otherwise we can be off by 1 byte if the sync arrives
* a bit early. This may happen due to timing mismatch or noise causing
* the sync word correlator to trigger early.
*/
[[gnu::noinline]]
void M17Demodulator::do_sync_wait()
{
if (sync_count < MAX_SYNC_COUNT)
{
sync_count += 1;
return;
}
need_clock_update_ = true;
demodState = DemodState::FRAME;
}
[[gnu::noinline]]
void M17Demodulator::do_frame(float filtered_sample, hdlc::IoFrame*& frame_result)
{
// Only do this when there is no chance of skipping a sample. So do
// this update as far from the sample point as possible. It should
// only ever change by +/- 1.
if (abs(int(sample_index - correlator.index())) == (SAMPLES_PER_SYMBOL / 2))
{
clock_recovery.update();
sample_index = clock_recovery.sample_index();
return;
}
if (correlator.index() != sample_index) return;
float sample = filtered_sample - dev.offset();
sample *= idev;
float sample = dev.normalize(filtered_sample);
dev.update(sample);
auto n = mobilinkd::llr<float, 4>(sample);
int8_t* tmp;
auto len = framer(n, &tmp);
if (len != 0)
{
need_clock_update_ = true;
sync_count = 0;
std::copy(tmp, tmp + len, buffer.begin());
auto valid = decoder(sync_word_type, buffer, frame_result, ber);
INFO("demod: %d, dt: %7d, evma: %5d, dev: %5d, freq: %5d, index: %d, %d, %d ber: %d",
INFO("demod: %d, dt: %4dppm, evma: %5d‰, dev: %5d, freq: %5d, dcd: %d, index: %d, %d ber: %d",
int(decoder.state()), int(clock_recovery.clock_estimate() * 1000000),
int(dev.error() * 1000), int(dev.deviation() * 1000),
int(dev.offset() * 1000),
int(sample_index), int(clock_recovery.sample_index()), int(sync_sample_index),
int(dev.offset() * 1000), int(dcd.level() * 1000),
int(clock_recovery.sample_index()), int(sync_sample_index),
ber);
switch (decoder.state())
@ -399,8 +540,6 @@ void M17Demodulator::do_frame(float filtered_sample, hdlc::IoFrame*& frame_resul
break;
}
sync_count = 0;
switch (valid)
{
case M17FrameDecoder::DecodeResult::FAIL:
@ -411,10 +550,6 @@ void M17Demodulator::do_frame(float filtered_sample, hdlc::IoFrame*& frame_resul
frame_result = nullptr;
}
break;
case M17FrameDecoder::DecodeResult::EOS:
demodState = DemodState::LSF_SYNC;
INFO("EOS");
break;
case M17FrameDecoder::DecodeResult::OK:
break;
case M17FrameDecoder::DecodeResult::INCOMPLETE:
@ -460,40 +595,29 @@ hdlc::IoFrame* M17Demodulator::operator()(const q15_t* input)
for (size_t i = 0; i != ADC_BLOCK_SIZE; ++i)
{
auto filtered_sample = filtered[i];
auto filtered_sample = dc_block(filtered[i]);
correlator.sample(filtered_sample);
if (correlator.index() == 0)
{
if (need_clock_reset_)
{
clock_recovery.reset();
clock_recovery.reset(sync_sample_index);
need_clock_reset_ = false;
sample_index = sync_sample_index;
adc_timing_adjust = 0;
}
else if (need_clock_update_) // must avoid update immediately after reset.
{
clock_recovery.update();
uint8_t clock_index = clock_recovery.sample_index();
uint8_t clock_diff = std::abs(sample_index - clock_index);
uint8_t sync_diff = std::abs(sample_index - sync_sample_index);
bool clock_diff_ok = clock_diff <= 1 || clock_diff == 9;
bool sync_diff_ok = sync_diff <= 1 || sync_diff == 9;
if (clock_diff_ok) sample_index = clock_index;
else if (sync_diff_ok) sample_index = sync_sample_index;
// else unchanged.
// We have a valid sync word. Update the filter.
clock_recovery.update(sync_sample_index);
need_clock_update_ = false;
}
}
// Do this here, after the potential clock recovery reset above.
clock_recovery(filtered_sample);
if (demodState != DemodState::UNLOCKED && correlator.index() == sample_index)
{
dev.sample(filtered_sample);
}
switch (demodState)
{
case DemodState::UNLOCKED:
@ -514,6 +638,9 @@ hdlc::IoFrame* M17Demodulator::operator()(const q15_t* input)
case DemodState::BERT_SYNC:
do_bert_sync();
break;
case DemodState::SYNC_WAIT:
do_sync_wait();
break;
case DemodState::FRAME:
do_frame(filtered_sample,frame_result);
break;

Wyświetl plik

@ -1,4 +1,4 @@
// Copyright 2020-2021 Rob Riggs <rob@mobilinkd.com>
// Copyright 2020-2022 Rob Riggs <rob@mobilinkd.com>
// All rights reserved.
#pragma once
@ -44,22 +44,28 @@ struct M17Demodulator : IDemodulator
static constexpr float sample_rate = SAMPLE_RATE;
static constexpr float symbol_rate = SYMBOL_RATE;
static constexpr uint8_t MAX_MISSING_SYNC = 5;
static constexpr int STREAM_COST_LIMIT = 80;
static constexpr int PACKET_COST_LIMIT = 60;
static constexpr uint8_t MAX_MISSING_SYNC = 10;
static constexpr uint8_t MIN_SYNC_COUNT = 78;
static constexpr uint8_t MAX_SYNC_COUNT = 87;
static constexpr float EOT_TRIGGER_LEVEL = 0.1;
using audio_filter_t = FirFilter<ADC_BLOCK_SIZE, m17::FILTER_TAP_NUM_15>;
using audio_filter_t = FirFilter<ADC_BLOCK_SIZE, m17::FILTER_TAP_NUM>;
using sync_word_t = m17::SyncWord<m17::Correlator>;
enum class DemodState { UNLOCKED, LSF_SYNC, STREAM_SYNC, PACKET_SYNC, BERT_SYNC, FRAME };
enum class DemodState { UNLOCKED, LSF_SYNC, STREAM_SYNC, PACKET_SYNC, BERT_SYNC, SYNC_WAIT, FRAME };
audio_filter_t demod_filter;
std::array<float, ADC_BLOCK_SIZE> demod_buffer;
m17::DataCarrierDetect<float, SAMPLE_RATE, 500> dcd{2500, 4000, 1.0, 10.0};
m17::ClockRecovery<float, SAMPLE_RATE, SYMBOL_RATE> clock_recovery;
m17::DataCarrierDetect<float, SAMPLE_RATE, 400> dcd{2400, 4800, 0.8f, 10.0f};
m17::ClockRecovery<float, SAMPLES_PER_SYMBOL> clock_recovery;
m17::Correlator correlator;
sync_word_t preamble_sync{{+3,-3,+3,-3,+3,-3,+3,-3}, 29.f};
sync_word_t lsf_sync{{+3,+3,+3,+3,-3,-3,+3,-3}, 31.f, -31.f};
sync_word_t packet_sync{{3,-3,3,3,-3,-3,-3,-3}, 31.f, -31.f};
sync_word_t eot_sync{{+3,+3,+3,+3,+3,+3,-3,+3}, 31.f};
m17::FreqDevEstimator<float> dev;
@ -70,7 +76,6 @@ struct M17Demodulator : IDemodulator
DemodState demodState = DemodState::UNLOCKED;
M17FrameDecoder::SyncWordType sync_word_type = M17FrameDecoder::SyncWordType::LSF;
uint8_t sample_index = 0;
float idev;
bool dcd_ = false;
bool need_clock_reset_ = false;
@ -82,7 +87,6 @@ struct M17Demodulator : IDemodulator
uint16_t missing_sync_count = 0;
uint8_t sync_sample_index = 0;
int16_t adc_timing_adjust = 0;
float prev_clock_estimate = 1.;
virtual ~M17Demodulator() {}
@ -98,6 +102,7 @@ struct M17Demodulator : IDemodulator
void do_packet_sync();
void do_stream_sync();
void do_bert_sync();
void do_sync_wait();
void do_frame(float filtered_sample, hdlc::IoFrame*& frame_result);
void stop() override

Wyświetl plik

@ -161,7 +161,7 @@ struct M17FrameDecoder
enum class State {LSF, STREAM, BASIC_PACKET, FULL_PACKET, BERT};
enum class SyncWordType { LSF, STREAM, PACKET, BERT };
enum class DecodeResult { FAIL, OK, EOS, INCOMPLETE };
enum class DecodeResult { FAIL, OK, INCOMPLETE };
State state_ = State::LSF;
@ -282,7 +282,6 @@ struct M17FrameDecoder
{
depuncture(buffer, tmp.lsf, P1);
ber = viterbi_.decode(tmp.lsf, output.lsf);
ber = ber > 60 ? ber - 60 : 0;
detail::to_bytes(output.lsf, current_lsf);
crc_.reset();
for (auto c : current_lsf) crc_(c);
@ -361,13 +360,24 @@ struct M17FrameDecoder
uint8_t fragment_number = tmp.lich[5]; // Get fragment number.
fragment_number = (fragment_number >> 5) & 7;
if (fragment_number > 5)
{
INFO("invalid LICH fragment %d", int(fragment_number));
ber = -1;
return DecodeResult::INCOMPLETE; // More to go...
}
// Copy decoded LICH to superframe buffer.
std::copy(tmp.lich.begin(), tmp.lich.begin() + 5,
output.lich.begin() + (fragment_number * 5));
lich_segments |= (1 << fragment_number); // Indicate segment received.
INFO("got segment %d, have %02x", int(fragment_number), int(lich_segments));
if (lich_segments != 0x3F) return DecodeResult::INCOMPLETE; // More to go...
if ((lich_segments & 0x3F) != 0x3F)
{
ber = -1;
return DecodeResult::INCOMPLETE; // More to go...
}
crc_.reset();
for (auto c : output.lich) crc_(c);
@ -431,13 +441,6 @@ struct M17FrameDecoder
if (ber < 128) stream->push_back(255 - ber * 2);
else stream->push_back(0);
if ((ber < 60) && (stream_segment[0] & 0x80))
{
INFO("EOS");
state_ = State::LSF;
result = DecodeResult::EOS;
}
// Bogus CRC bytes to be dropped.
stream->push_back(0);
stream->push_back(0);
@ -603,17 +606,17 @@ struct M17FrameDecoder
* When in STREAM mode, the state machine can transition to either:
*
* - STREAM when a any stream frame is received.
* - LSF when the EOS indicator is set, or when a packet frame is received.
* - LSF when reset().
*
* When in BASIC_PACKET mode, the state machine can transition to either:
*
* - BASIC_PACKET when any packet frame is received.
* - LSF when the EOS indicator is set, or when a stream frame is received.
* - LSF when a complete paket superframe is received.
*
* When in FULL_PACKET mode, the state machine can transition to either:
*
* - FULL_PACKET when any packet frame is received.
* - LSF when the EOS indicator is set, or when a stream frame is received.
* - LSF when a complete packet superframe is received.
*/
[[gnu::noinline]]
DecodeResult operator()(SyncWordType frame_type, buffer_t& buffer,

Wyświetl plik

@ -11,10 +11,10 @@ void M17Modulator::init(const kiss::Hardware& hw)
(void) hw; // unused
SysClock72();
SysClock48();
// Configure 72MHz clock for 48kHz.
htim7.Init.Period = 1499;
htim7.Init.Period = 999;
htim7.Init.Prescaler = 0;
if (HAL_TIM_Base_Init(&htim7) != HAL_OK)
{

Wyświetl plik

@ -26,7 +26,9 @@ struct M17Modulator : Modulator
// Six buffers per M17 frame, or 12 half-buffer interrupts.
static constexpr uint8_t UPSAMPLE = 10;
static constexpr uint32_t BLOCKSIZE = 4;
static constexpr uint32_t STATE_SIZE = (m17::FILTER_TAP_NUM_15 / UPSAMPLE) + BLOCKSIZE - 1;
static constexpr uint32_t STATE_SIZE = (m17::FILTER_TAP_NUM / UPSAMPLE) + BLOCKSIZE - 1;
// Number of bytes (4 symbol groups) to flush the FIR filter.
static constexpr uint8_t FLUSH_LEN = ((m17::FILTER_TAP_NUM / UPSAMPLE) + 3) / 4;
static constexpr int16_t DAC_BUFFER_LEN = 80; // 8 symbols, 16 bits, 2 bytes.
static constexpr int16_t TRANSFER_LEN = DAC_BUFFER_LEN / 2; // 4 symbols, 8 bits, 1 byte.
static constexpr uint16_t VREF = 4095;
@ -49,8 +51,8 @@ struct M17Modulator : Modulator
: dacOutputQueueHandle_(queue), ptt_(ptt)
{
arm_fir_interpolate_init_f32(
&fir_interpolator, UPSAMPLE, m17::FILTER_TAP_NUM_15,
(float32_t*) m17::rrc_taps_f15.data(), fir_state.data(), BLOCKSIZE);
&fir_interpolator, UPSAMPLE, m17::FILTER_TAP_NUM,
(float32_t*) m17::rrc_taps_f.data(), fir_state.data(), BLOCKSIZE);
}
~M17Modulator() override {}
@ -118,7 +120,7 @@ struct M17Modulator : Modulator
start_conversion();
ptt_->on();
while (delay_count < txdelay) osThreadYield();
stop_count = 4; // 16 symbols to flush the RRC filter.
stop_count = FLUSH_LEN;
osMessagePut(dacOutputQueueHandle_, bits, osWaitForever);
state = State::RUNNING;
break;

Wyświetl plik

@ -1,4 +1,4 @@
// Copyright 2020 Mobilinkd LLC <rob@mobilinkd.com>
// Copyright 2020-2022 Mobilinkd LLC <rob@mobilinkd.com>
// All rights reserved.
#pragma once
@ -56,4 +56,32 @@ struct StandardDeviation
}
};
template <typename FloatType, size_t N>
struct RunningStandardDeviation
{
FloatType S{1.0};
FloatType alpha{1.0 / N};
void reset()
{
S = 0.0;
}
void capture(float sample)
{
S -= S * alpha;
S += (sample * sample) * alpha;
}
FloatType variance() const
{
return S;
}
FloatType stdev() const
{
return std::sqrt(variance());
}
};
} // mobilinkd

Wyświetl plik

@ -0,0 +1,124 @@
// Copyright 2021 Mobilinkd LLC.
#pragma once
#include "Log.h"
#include <arm_math.h>
#include <algorithm>
#include <array>
#include <cassert>
#include <cstddef>
#include <cstdint>
#include <iterator>
#include <numeric>
namespace mobilinkd { namespace m17 {
/**
* Calculate the phase estimates for each sample position.
*
* This performs a running calculation of the phase of each bit position.
* It is very noisy for individual samples, but quite accurate when
* averaged over an entire M17 frame.
*
* It is designed to be used to calculate the best bit position for each
* frame of data. Samples are collected and averaged. When update() is
* called, the best sample index and clock are estimated, and the counters
* reset for the next frame.
*
* It starts counting bit 0 as the first bit received after a reset.
*
* This is very efficient as it only uses addition and subtraction for
* each bit sample. And uses one multiply and divide per update (per
* frame).
*
* This will permit a clock error of up to 500ppm. This allows up to
* 250ppm error for both transmitter and receiver clocks. This is
* less than one sample per frame when the sample rate is 48000 SPS.
*
* @inv current_index_ is in the interval [0, SAMPLES_PER_SYMBOL).
* @inv sample_index_ is in the interval [0, SAMPLES_PER_SYMBOL).
* @inv clock_ is in the interval [0.9995, 1.0005]
*/
template <typename FloatType = float, size_t SamplesPerSymbol = 10>
struct SymbolSlopeIntegrator
{
static constexpr std::array<FloatType, 5> IMPULSE = {
-1.0, -0.70710678, 0.0, 0.70710678, 1.0
};
static constexpr size_t BEGIN = SamplesPerSymbol / 2 + IMPULSE.size() / 2;
static constexpr size_t END = BEGIN + SamplesPerSymbol;
std::array<FloatType, SamplesPerSymbol> integrator_;
std::array<FloatType, SamplesPerSymbol * 2> signal;
std::array<FloatType, SamplesPerSymbol * 2 + IMPULSE.size() - 1> output;
FloatType prev_ = 0.0;
size_t index_ = 0;
void reset()
{
integrator_.fill(0.0);
prev_ = 0.0;
index_ = 0;
}
void operator()(FloatType value)
{
auto dy = value - prev_;
// Invert the phase estimate when sample midpoint is less than 0.
integrator_[index_] += value < 0 ? -dy : dy;
index_ = (index_ == (SamplesPerSymbol - 1)) ? 0 : index_ + 1;
prev_ = value;
}
[[gnu::noinline]]
int8_t update()
{
// Circular convolution, so we concatenate the signal back-to-back.
// This is effectively "wrap" convolution, just offset by
// (SamplesPerSignal + IMPULSE.size()) / 2.
auto it = std::copy(integrator_.begin(), integrator_.end(), signal.begin());
std::copy(integrator_.begin(), integrator_.end(), it);
arm_conv_f32(signal.data(), signal.size(),
(float*)IMPULSE.data(), IMPULSE.size(),
output.data());
auto argmax = std::max_element(&output[BEGIN], &output[END]);
int8_t index = std::distance(&output[BEGIN], argmax);
// Normalize index from wrapped position.
index -= SamplesPerSymbol / 2;
if (index < 0) index += SamplesPerSymbol;
#if 1
INFO("output: %5d, %5d, %5d, %5d, %5d, %5d, %5d, %5d, %5d, %5d",
int(output[7]*1000), int(output[8]*1000), int(output[9]*1000), int(output[10]*1000), int(output[11]*1000),
int(output[12]*1000), int(output[13]*1000), int(output[14]*1000), int(output[15]*1000), int(output[16]*1000));
INFO("Index = %d", index);
#endif
// Reset integrator for next frame.
integrator_.fill(0.0);
return index;
}
/**
* Return the current sample index. This will always be in the range of
* [0..SAMPLES_PER_SYMBOL).
*/
uint8_t current_index() const
{
return index_;
}
};
}} // mobilinkd::m17

Wyświetl plik

@ -211,7 +211,7 @@ struct Viterbi
size_t min_element = 0;
int32_t min_cost = prevMetrics[0];
for (size_t i = 0; i != NumStates; ++i)
for (size_t i = 1; i != NumStates; ++i)
{
if (prevMetrics[i] < min_cost)
{

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 212 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 73 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 55 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 1.2 MiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 138 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 120 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 248 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 109 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 88 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 219 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 251 KiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 1.8 MiB

Plik binarny nie jest wyświetlany.

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 1.2 MiB

Wyświetl plik

@ -0,0 +1,507 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Mobilinkd M17 Setup Guide\n",
"\n",
"This is a guide on how to properly configure and use the Mobilinkd TNC3\n",
"for M17 voice and data communication.\n",
"\n",
"This guide assumes that you will be using the TNC3 with a suitable\n",
"9600-baud capable radio, and that you have the proper cable to\n",
"connect the TNC3 to the radio. It also assumes that you will be\n",
"using the [M17-KISS-HT](https://github.com/mobilinkd/m17-kiss-ht)\n",
"Android app for voice communications.\n",
"\n",
"The guide assumes familiarity with GNU Radio for the M17 receive\n",
"tests. And it assumes that you can side-load apps to your Android\n",
"device.\n",
"\n",
"This is very much a guide for the experienced experimenter, and not\n",
"a step-by-step guide designed for beginners.\n",
"\n",
"I will gladly accept pull requests for added detail for any of the\n",
"sections below, or for setup hints for specific radio models.\n",
"\n",
"## Required Tools\n",
"\n",
" 1. An RTL-SDR (TCXO-based, or well-characterized) with antenna.\n",
" 1. A Pluto SDR with accurate timebase (or other suitable transmit-capable SDR)\n",
" 1. A Linux-based computer with working sound system\n",
" 1. The `rtl-sdr` package installed, which contains `/usr/bin/rtl_fm`.\n",
" 1. [m17-cxx-demod](https://github.com/mobilinkd/m17-cxx-demod) built for Linux\n",
" 1. GQRX or other GUI-based software for viewing the spectrum by an RTL-SDR\n",
" 1. A working GNU Radio installation with gr-iio (or sink for your SDR transmitter)\n",
" 1. Android device running a recent version of Android (10 or greater)\n",
" 1. The Mobilinkd Config App installed on the Android device\n",
" 1. M17-KISS-HT installed on the Android device (must be side-loaded)\n",
" 1. A USB-OTG adapter for the Android device, and an USB cable to connect to the TNC\n",
" 1. A dummy load\n",
" \n",
"Please note that both SDRs will require accurate reference clocks.\n",
"4-FSK requires reasonably accurate transmit and receive frequencies to\n",
"be decoded properly. If your SDR has a 20ppm clock, you can be off by\n",
"8kHz on 70cm. It will be impossible to tune the system properly with\n",
"such an error. The maximum error that will work is about 500Hz, and\n",
"less than 100Hz is preferred. That's a 1ppm error, max, at 70cm.\n",
"\n",
"We will be connecting to the TNC via USB-OTG rather than over BLE\n",
"as it been considerably more reliable. The BLE connection has been\n",
"unreliable on certain phones and Android versions.\n",
"\n",
"### Recommended Tools\n",
"\n",
" 1. RF filters for the transmit SDR\n",
" 1. RF attenuators 20-40dB\n",
" 1. Spectrum Analyzer\n",
" 1. Cables and adapters that allow connecting the SDR to\n",
" the radio through an attenuator.\n",
" \n",
"## Overview\n",
"\n",
"We will be performing the following steps:\n",
"\n",
" 1. Configure the TX deviation of the TNC/radio pair\n",
" 1. Configure the TX polarity of the TNC/radio pair\n",
" 1. Run a TX BERT (bit error rate test)\n",
" 1. Set up M17-KISS-HT\n",
" 1. Configure the RX polarity of the TNC/radio pair\n",
" 1. Run an RX BERT\n",
" 1. Transmit and receive voice\n",
"\n",
"## Resources\n",
"\n",
" * TNC3 Firmware: https://github.com/mobilinkd/tnc3-firmware/releases\n",
" * Mobilinkd Config App: https://play.google.com/store/apps/details?id=com.mobilinkd.tncconfig\n",
" * M17 KISS HT Android App: https://github.com/mobilinkd/m17-kiss-ht/releases\n",
" * M17 C++ Demodulator (m17-cxx-demod): https://github.com/mobilinkd/m17-cxx-demod/\n",
"\n",
"## Prep Work\n",
"\n",
"All of the detailed setup steps outlined in the sections below assume that\n",
"this prep work has been completed.\n",
"\n",
" * Connect the radio to a suitable dummy load.\n",
" * Install the M17 firmware (currently version 2.4.1) on the TNC3.\n",
" * Install the Mobilinkd Config app on the Android device.\n",
" * Side-load the M17 KISS HT app on the Android device.\n",
" * Pair the Mobilinkd TNC3 with the Android Device. Leave the TNC turned on.\n",
" * Connect the TNC3 to the radio.\n",
" * Turn on the radio and set it to the desired test frequency.\n",
" * Connect the RTL-SDR with an antenna to the computer.\n",
" * Connect the Pluto (with an antenna connected to the TX port) to the computer.\n",
" * Install GQRX and GNU Radio if not already installed.\n",
"\n",
"\n",
"### Configure the TNC3 for M17\n",
"\n",
"Open the Mobilinkd Config app, connect to the TNC, and go to *Modem Settings*.\n",
"\n",
"Select *M17 4-FSK* as the modem type.\n",
"\n",
"Select *Close*.\n",
"\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-modem-settings.png\" alt=\"TNC3 modem settings for M17\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"\n",
"Select *Save Settings*\n",
"\n",
"### Install and Build m17-cxx-demod\n",
"\n",
"Install the required libraries for m17-cxx-demod: boost-devel and codec2-devel.\n",
"These may be named differently on your Linux platform. `m17-cxx-demod` requires\n",
"the `codec2` library and the `Boost program-options` library.\n",
"\n",
"Clone the m17-cxx-demod repo and build the M17 C++ tools.\n",
"\n",
" git clone https://github.com/mobilinkd/m17-cxx-demod.git\n",
" cd m17-cxx-demod\n",
" mkdir build\n",
" cd build\n",
" cmake ..\n",
" make\n",
" make test\n",
"\n",
"## When Transmitting...\n",
"\n",
"Choose a test frequency that is unused and unlikely to interfere with\n",
"other amateur radio users.\n",
"\n",
"You may have an obligation to announce your callsign on the frequency that\n",
"you are transmitting on. If you are conducting open-air tests using an\n",
"antenna -- not via a dummy load or via direct coax connection between\n",
"radios -- you should announce at the start of the test, as frequently\n",
"as required by law, and when you are finished with the tests.\n",
"\n",
"## Mobilinkd Config App\n",
"\n",
"The *Audio Output Settings* of the Mobilinkd Config app was designed for\n",
"configuring 1200 baud AFSK audio levels. There are tone settings for\n",
"1200Hz, 2200Hz, and Both. Those settings are mapped as follows when\n",
"the TNC is in M17 mode:\n",
"\n",
" * 1200Hz -> 2400Hz (M17 Preamble)\n",
" * 2200Hz -> 1000Hz (M17 Deviation Aid)\n",
" * BOTH -> M17 BER Mode.\n",
"\n",
"BER mode implements the M17 BER testing specification.\n",
"\n",
"## Transmit Deviation\n",
"\n",
"This section assumes that you have completed the [Prep Work](#Prep-Work) steps above.\n",
"\n",
"**NOTE:** The preferred way to do this is with a spectrum analyzer instead of an\n",
"RTL-SDR and GQRX. Use an appropriately sized attenuator between the radio and the\n",
"instrument. Set the span to 50kHz and the RBW to 300Hz. Follow the output\n",
"adjustment procedure below.\n",
"\n",
"Start `GQRX` and tune to the desired frequency. The examples below use\n",
"144.910MHz for the test frequency.\n",
"\n",
"In the *Input Controls* tab, set the appropriate frequency correction factor\n",
"for your RTL-SDR. If you are not using an accurate TCXO, it must be set very\n",
"close to the PPM offset of your RTL-SDR. You need to be within 1PPM.\n",
"\n",
"In the *Receiver Options* tab, select Narrow FM in the *Mode* setting. Select\n",
"the \"...\" to the right of the *Mode* selection. Set the maximum deviation to\n",
"2.5kHz and the Tau factor to 0.\n",
"\n",
"In the *FFT Settings* tab, use the *Freq Zoom* slider to increase the zoom\n",
"factor to 10-20x. You may need to adjust this later while testing to get the\n",
"best view.\n",
"\n",
"Start the receiver using *Play* button.\n",
"\n",
"Open the Mobilinkd Config app on the Android device, connect to the TNC,\n",
"then select *Audio Output Settings*. Select the *2200Hz* for the *Output Tone*.\n",
"When in M17 mode, this will transmit a 1000Hz tone. A 1000Hz tone will create\n",
"the first Bessel null at 2405Hz deviation. This is very close to the value\n",
"needed for M17.\n",
"\n",
"Press the *Transmit* button. Observe the received spectrum in *GQRX*.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-audio-output.png\" alt=\"TNC3 audio output for M17\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"Adjust the output level until you see carrier (the middle peak) dip to its\n",
"lowest point. It may require careful adjustment of the slider on the app\n",
"as it was not really designed for such small adjustments that are required\n",
"here.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-bessel-null.png\" alt=\"GQRX Bessel null for M17\" style=\"width: 600px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"After the output setting has been adjusted to the desired level, press the\n",
"*Transmit* button to stop transmitting. Press *Close* to go back to the\n",
"main menu, then select *Save Settings*.\n",
"\n",
"Press the *Play* button in *GQRX* to stop the receiver. You can now exit *GQRX*.\n",
"\n",
"## Configure TX Polarity\n",
"\n",
"This section assumes that you have completed the [Prep Work](#Prep-Work) steps above. \n",
"\n",
"We are going to run rtl_fm and m17-cxx-demod to receive and decode M17 from the\n",
"TNC and radio. The TNC will sent a BER (bit error-rate) test sequence.\n",
"\n",
"Inside the `m17-cxx-demod/build` directory from earlier, run the following command:\n",
"\n",
" rtl_fm -F 9 -f 144.91M -s 18k | sox -t s16 -r 18k -c1 - -t raw - gain 9 rate -v -s 48k | ./apps/m17-demod -d -l > /dev/null\n",
"\n",
"You may need to set a `\"-p\"` option value for `rtl_fm` to adjust for the\n",
"clock error on your RTL-SDR dongle.\n",
"\n",
"Using a wide screen is best since it will output a wide diagnostics line. If the\n",
"terminal window is too narrow, it will scroll endlessly and be hard to read. A\n",
"width of 160 characters is about right.\n",
"\n",
" * Open the *Mobilinkd Config App* on the Android device.\n",
" * Connect to the TNC.\n",
" * Open *Audio Output Settings*.\n",
" * Select *Both* for the *Output Tone*. This will send a BER test sequence.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-tx-ber-test.png\" alt=\"M17 BER test for TX Polarity\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"Observe the results from the `m17-demod` program in the terminal window. A\n",
"good result will look something like this:\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-ber-test-2.png\" alt=\"M17 BER test for TX Polarity (good)\" style=\"width: 600px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"If, instead, you see something like the below result showing a high BER rate\n",
"(typically 80+), you likely need to change the polarity.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-ber-test-1.png\" alt=\"M17 BER test for TX Polarity (bad)\" style=\"width: 600px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"Stop transmitting, close the *Audio Output Settings* and open *Modem Settings*.\n",
"Enable the *TX Reverse Polarity* option. Then repeat the BER test above.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-tx-reverse-polarity.png\" alt=\"M17 setting TX Reverse Polarity\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"Stop transmitting. If the results look good after changing the polarity, go\n",
"back to the main menu and press *Save Settings*.\n",
"\n",
"If the results are still bad, check the frequency settings used on the radio and\n",
"on the command-line for `rtl_fm`. Verify the PPM settings on the RTL-SDR. Ensure\n",
"that your radio's VCO is properly calibrated and that it is transmitting and\n",
"receiving at the proper frequency.\n",
"\n",
"You can also reach out to #public-chat on the M17 Discord for help.\n",
"\n",
"In the Mobilindk Config app, press the *Disconnect* button to disconnect from\n",
"the TNC.\n",
"\n",
"## M17 KISS HT\n",
"\n",
"This section assumes that you have completed the [Prep Work](#Prep-Work) steps\n",
"above, including side loading of the *M17 KISS HT* app.\n",
"\n",
" * Ensure that there is no existing connection to the TNC.\n",
" * Connect the USB cable to the USB OTG adapter.\n",
" * Plug the USB OTG adapter into the Android device.\n",
" * Plug the USB cable into the Mobilinkd TNC.\n",
"\n",
"You should be presented with a dialog to open the connection with an app.\n",
"Choose the *M17 HT* app.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-usb-connection.png\" alt=\"M17 TNC USB Connection\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"The first thing you need to do in order to use the app is to set your\n",
"callsign. This can include a suffix designator. Here you see that I\n",
"chose \"WX9O-8\" to distinguish this connection.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-kiss-ht-callsign.png\" alt=\"M17 KISS HT Callsign\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"### Voice Transmission\n",
"\n",
"We are going to run the m17-cxx-demod program again, this time taking the\n",
"demodulated output and sending it to the computer's sound system.\n",
"\n",
" rtl_fm -F 9 -f 144.91M -s 18k | sox -t s16 -r 18k -c1 - -t raw - gain 9 rate -v -s 48k | ./apps/m17-demod -d -l | play -b 16 -r 8000 -c1 -t s16 -\n",
"\n",
"This is the same command used for BER testing and setting up the TX polarity,\n",
"except we are now piping the output to the computer's audio output.\n",
"\n",
"Press the transmit button on the M17 HT app. The Transmit button can act\n",
"like a toggle button or a push button. A short press locks the transmit\n",
"button. Another short press disengages the transmit button. If instead you\n",
"hold the button for longer than 1/2 second, it acts as a push button and will\n",
"stop transmitting as soon as you release the button.\n",
"\n",
"Press the transmit button, speak, then release the transmit button. It is\n",
"likely that you will hear a long delay before the received audio plays. This\n",
"is because the pipeline used in the command above has high latency due to\n",
"the buffers in each stage of the pipeline.\n",
"\n",
"You should hear your voice and see something like this in the terminal window.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-ht-voice-transmit.png\" alt=\"M17 KISS Voice Transmit Test\" style=\"width: 600px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"Notice that the callsign you entered into the M17 HT app was decoded.\n",
"\n",
"The long audio delay can be reduced somewhat by using `stdbuf`. This makes the\n",
"command-line a bit unwieldy.\n",
"\n",
" stdbuf -o0 rtl_fm -F 9 -f 144.91M -s 18k | stdbuf -i0 -o0 sox --buffer 24 -t s16 -r 18k -c1 - -t raw - gain 9 rate -v -s 48k | stdbuf -i0 -o0 ./apps/m17-demod -d -l -b | stdbuf -i0 play --buffer 24 -q -b 16 -r 8000 -c1 -t s16 -\n",
"\n",
"### M17 BER Receive Test\n",
"\n",
"For this test you will need the `m17-gnuradio` repo cloned.\n",
"\n",
"**NOTE:** If you are using an SDR other than an ADALM Pluto, please\n",
"verify that the output polarity is correct first by attempting to\n",
"receive it using the method outline in [Configure TX Polarity](#Configure-TX-Polarity).\n",
"\n",
"Set up your ADALM Pluto or other transmit-capable SDR. Install any required\n",
"filters and transmit antenna. If you can, connect the SDR to the radio\n",
"under test through a 30dB or 40dB attenuator. *Be very careful if you do\n",
"connect the SDR to the radio because it is very easy to damage the SDR\n",
"if the radio transmits.*\n",
"\n",
"Open *GNU Radio Companion* (GRC) and within that, open the `m17-bert.grc` file.\n",
"Adjust the output sink paramters (including the frequency) for the test. You\n",
"may need to adjust the pathnam in the *File Source* block so that the `bert.bin` \n",
"file can be found. The path is typically relative to your HOME directory.\n",
"\n",
"Once done, click the *Play* button on GRC. It should start transmitting a\n",
"BER test sequence similar to the one transmitted by the Mobilinkd Config app.\n",
"\n",
"Connect the TNC to the Android device via the USB-OTG connection used earlier.\n",
"Once connected, the TNC should start receiving the BER test sequence. It is\n",
"likely that you will see some error if you start receiving in the middle of\n",
"the test sequence.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-rx-ber-test.png\" alt=\"M17 KISS BER Test\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"If you do not see the app go into BER test mode, you will need to troubleshoot\n",
"the issue.\n",
"\n",
" 1. Verify that the receive indicator on the TNC is green. If not, check the\n",
" transmit frequency and transmit power levels. Check the radio's receive\n",
" frequency is correct and that it is not set for a repeater split.\n",
" 1. If the receive indicator is green, disconnect the USB OTG cable from\n",
" the Android device. Open the Mobilinkd Config app. Connect to the TNC.\n",
" Select *Modem Settings*, then enable `RX Reverse Polarity`. Press *Close*\n",
" and then *Save Settings*. Repeat the experiment.\n",
" 1. Try reducing the attenuation in the *PlutoSDR Sink* block.\n",
"\n",
"### Voice Reception\n",
"\n",
"The voice reception test is quite similar to the BER test above. It is another\n",
"GNU Radio flowgraph that transmits a long-form English language voice program\n",
"for amateur radio.\n",
"\n",
"This assumes the ADALM Pluto, radio and TNC are configured the same as with\n",
"the BER Receive Test. If it is not, follow the setup steps in that section.\n",
"\n",
"Open *GNU Radio Companion* (GRC) and within that, open the `m17-arn.grc` file.\n",
"Adjust the output sink paramters (including the frequency) for the test. You\n",
"may need to adjust the pathnam in the *File Source* block so that the `Report2288.bin` \n",
"file can be found. The path is typically relative to your HOME directory.\n",
"\n",
"Connect the TNC to the Android device via the USB-OTG connection used earlier.\n",
"This should start the M17 HT app.\n",
"\n",
"Click the *Play* button on GRC. It will start transmitting a voice program,\n",
"which you should hear being received on the Android device.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/m17-rx-voice-test.png\" alt=\"M17 KISS HT Voice Receive Test\" style=\"width: 300px;\"/> </td>\n",
" </tr>\n",
"</table>"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# M17 Radio Configuration Hints\n",
"\n",
"Add instructions and hints for configuring various radios for use with M17 below."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Yaesu FT-991\n",
"\n",
"This section outlines set up steps and some issues with the Yeasu FT-991.\n",
"\n",
"### Radio Setup Steps\n",
"\n",
"Press the *Menu* button and adjust the following settings to use the packet data port for M17:\n",
"\n",
" * Set `75 FM OUT LEVEL` to `100`\n",
" * Set `76 FM PKT PTT SELECT` to `DAKY`\n",
" * Set `77 FM PKT PORT SELECT` to `DATA`\n",
" * Set `78 FM PKT TX GAIN` to `64`\n",
" * Set `79 FM PKT MODE` to `9600`\n",
" \n",
"Press the *Menu* button again to go back to the main screen.\n",
"\n",
"Press the *Mode* button and select `DATA-FM`. Press *Mode* again to go back to the main screen.\n",
"\n",
"### TNC Setup Steps\n",
"\n",
"In *Audio Input Settings*, set the `Input Gain` value to 3.\n",
"\n",
"In *Modem Settings*, enable the `TX Reverse Polarity` option for this radio.\n",
"\n",
"### Known Issues\n",
"\n",
"#### Low Output Level\n",
"\n",
"The demodulated baseband signal from the *DATA-FM* mode is very low. It\n",
"is an order of magnitude lower than in pure *FM* mode. There is a lot of\n",
"high-frequency noise in the signal.\n",
"\n",
"#### Frequency Stability\n",
"\n",
"On my unit, the frequency stability when it first starts transmitting is rather poor.\n",
"\n",
"<table>\n",
" <tr>\n",
" <td> <img src=\"images/wobbly-freq-accuracy.png\" alt=\"FT-991 wobbly frequency\" style=\"width: 600px;\"/> </td>\n",
" </tr>\n",
"</table>\n",
"\n",
"Note the wobbly lines at the start of the transmission. This lasts for a few\n",
"seconds. It can cause a burst of bit errors at the start of the transmission."
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.9.7"
}
},
"nbformat": 4,
"nbformat_minor": 4
}