Merge branch 'AX25_FM' into M17_AX25_FM

This commit is contained in:
Jonathan Naylor 2020-11-06 15:06:00 +00:00
commit 55c89a4413
81 changed files with 3695 additions and 2077 deletions

36
AX25Defines.h Normal file
View File

@ -0,0 +1,36 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(AX25DEFINES_H)
#define AX25DEFINES_H
const uint8_t AX25_RADIO_SYMBOL_LENGTH = 20U; // At 24 kHz sample rate
const uint8_t AX25_FRAME_START = 0x7EU;
const uint8_t AX25_FRAME_END = 0x7EU;
const uint8_t AX25_FRAME_ABORT = 0xFEU;
const uint8_t AX25_MAX_ONES = 5U;
const uint16_t AX25_MIN_FRAME_LENGTH = 17U; // Callsign (7) + Callsign (7) + Control (1) + Checksum (2)
const uint16_t AX25_MAX_FRAME_LENGTH = 330U; // Callsign (7) + Callsign (7) + 8 Digipeaters (56) +
// Control (1) + PID (1) + Data (256) + Checksum (2)
#endif

314
AX25Demodulator.cpp Normal file
View File

@ -0,0 +1,314 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright 2015-2019 Mobilinkd LLC <rob@mobilinkd.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "AX25Demodulator.h"
#include "AX25Defines.h"
const float32_t SAMPLE_RATE = 24000.0F;
const float32_t SYMBOL_RATE = 1200.0F;
const uint16_t DELAY_LEN = 11U;
const float32_t SAMPLES_PER_SYMBOL = SAMPLE_RATE / SYMBOL_RATE;
const float32_t PLL_LIMIT = SAMPLES_PER_SYMBOL / 2.0F;
const uint32_t LPF_FILTER_LEN = 48U;
q15_t LPF_FILTER_COEFFS[] = {
-2, -8, -17, -28, -40, -47, -47, -34,
-5, 46, 122, 224, 354, 510, 689, 885,
1092, 1302, 1506, 1693, 1856, 1987, 2077, 2124,
2124, 2077, 1987, 1856, 1693, 1506, 1302, 1092,
885, 689, 510, 354, 224, 122, 46, -5,
-34, -47, -47, -40, -28, -17, -8, -2
};
// Lock low-pass filter taps (80Hz Bessel)
// scipy.signal:
// b, a = bessel(4, [80.0/(1200/2)], 'lowpass')
//
const uint8_t PLL_IIR_SIZE = 5U;
const float32_t PLL_LOCK_B[] = {
1.077063e-03,4.308253e-03,6.462379e-03,4.308253e-03,1.077063e-03};
const float32_t PLL_LOCK_A[] = {
1.000000e+00,-2.774567e+00,2.962960e+00,-1.437990e+00,2.668296e-01};
// 64 Hz loop filter.
// scipy.signal:
// loop_coeffs = firwin(9, [64.0/(1200/2)], width = None,
// pass_zero = True, scale = True, window='hann')
//
const uint32_t PLL_FILTER_LEN = 7U;
float32_t PLL_FILTER_COEFFS[] = {3.196252e-02F, 1.204223e-01F, 2.176819e-01F, 2.598666e-01F, 2.176819e-01F, 1.204223e-01F, 3.196252e-02F};
CAX25Demodulator::CAX25Demodulator(int8_t n) :
m_frame(),
m_twist(n),
m_lpfFilter(),
m_lpfState(),
m_delayLine(NULL),
m_delayPos(0U),
m_nrziState(false),
m_pllFilter(),
m_pllState(),
m_pllLast(false),
m_pllBits(1U),
m_pllCount(0.0F),
m_pllJitter(0.0F),
m_pllDCD(false),
m_iirHistory(),
m_hdlcOnes(0U),
m_hdlcFlag(false),
m_hdlcBuffer(0U),
m_hdlcBits(0U),
m_hdlcState(AX25_IDLE)
{
m_delayLine = new bool[DELAY_LEN];
m_lpfFilter.numTaps = LPF_FILTER_LEN;
m_lpfFilter.pState = m_lpfState;
m_lpfFilter.pCoeffs = LPF_FILTER_COEFFS;
m_pllFilter.numTaps = PLL_FILTER_LEN;
m_pllFilter.pState = m_pllState;
m_pllFilter.pCoeffs = PLL_FILTER_COEFFS;
for (uint8_t i = 0U; i < PLL_IIR_SIZE; i++)
m_iirHistory[i] = 0.0F;
}
bool CAX25Demodulator::process(q15_t* samples, uint8_t length, CAX25Frame& frame)
{
bool result = false;
q15_t fa[RX_BLOCK_SIZE];
m_twist.process(samples, fa, RX_BLOCK_SIZE);
int16_t buffer[RX_BLOCK_SIZE];
for (uint8_t i = 0; i < length; i++) {
bool level = (fa[i] >= 0);
bool delayed = delay(level);
buffer[i] = (int16_t(level ^ delayed) << 1) - 1;
}
q15_t fc[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_lpfFilter, buffer, fc, RX_BLOCK_SIZE);
for (uint8_t i = 0; i < length; i++) {
bool bit = fc[i] >= 0;
bool sample = PLL(bit);
if (sample) {
// We will only ever get one frame because there are
// not enough bits in a block for more than one.
if (result) {
HDLC(NRZI(bit));
} else {
result = HDLC(NRZI(bit));
if (result) {
// Copy the frame data.
::memcpy(frame.m_data, m_frame.m_data, AX25_MAX_PACKET_LEN);
frame.m_length = m_frame.m_length;
frame.m_fcs = m_frame.m_fcs;
m_frame.m_length = 0U;
}
}
}
}
return result;
}
bool CAX25Demodulator::delay(bool b)
{
bool r = m_delayLine[m_delayPos];
m_delayLine[m_delayPos++] = b;
if (m_delayPos >= DELAY_LEN)
m_delayPos = 0U;
return r;
}
bool CAX25Demodulator::NRZI(bool b)
{
bool result = (b == m_nrziState);
m_nrziState = b;
return result;
}
bool CAX25Demodulator::PLL(bool input)
{
bool sample = false;
if (input != m_pllLast || m_pllBits > 16U) {
// Record transition.
m_pllLast = input;
if (m_pllCount > PLL_LIMIT)
m_pllCount -= SAMPLES_PER_SYMBOL;
float32_t adjust = m_pllBits > 16U ? 5.0F : 0.0F;
float32_t offset = m_pllCount / float32_t(m_pllBits);
float32_t jitter;
::arm_fir_f32(&m_pllFilter, &offset, &jitter, 1U);
float32_t absOffset = adjust;
if (offset < 0.0F)
absOffset -= offset;
else
absOffset += offset;
m_pllJitter = iir(absOffset);
m_pllCount -= jitter / 2.0F;
m_pllBits = 1U;
} else {
if (m_pllCount > PLL_LIMIT) {
sample = true;
m_pllCount -= SAMPLES_PER_SYMBOL;
m_pllBits++;
}
}
m_pllCount += 1.0F;
return sample;
}
bool CAX25Demodulator::HDLC(bool b)
{
if (m_hdlcOnes == AX25_MAX_ONES) {
if (b) {
// flag byte
m_hdlcFlag = true;
} else {
// bit stuffing...
m_hdlcFlag = false;
m_hdlcOnes = 0U;
return false;
}
}
m_hdlcBuffer >>= 1;
m_hdlcBuffer |= b ? 128U : 0U;
m_hdlcBits++; // Free-running until Sync byte.
if (b)
m_hdlcOnes++;
else
m_hdlcOnes = 0U;
if (m_hdlcFlag) {
bool result = false;
switch (m_hdlcBuffer) {
case AX25_FRAME_END:
if (m_frame.m_length >= AX25_MIN_FRAME_LENGTH) {
result = m_frame.checkCRC();
if (!result)
m_frame.m_length = 0U;
} else {
m_frame.m_length = 0U;
}
m_hdlcState = AX25_SYNC;
m_hdlcFlag = false;
m_hdlcBits = 0U;
break;
case AX25_FRAME_ABORT:
// Frame aborted
m_frame.m_length = 0U;
m_hdlcState = AX25_IDLE;
m_hdlcFlag = false;
m_hdlcBits = 0U;
break;
default:
break;
}
return result;
}
switch (m_hdlcState) {
case AX25_IDLE:
break;
case AX25_SYNC:
if (m_hdlcBits == 8U) { // 8th bit.
// Start of frame data.
m_hdlcState = AX25_RECEIVE;
m_frame.append(m_hdlcBuffer);
m_hdlcBits = 0U;
}
break;
case AX25_RECEIVE:
if (m_hdlcBits == 8U) { // 8th bit.
m_frame.append(m_hdlcBuffer);
m_hdlcBits = 0U;
}
break;
default:
break;
}
return false;
}
void CAX25Demodulator::setTwist(int8_t n)
{
m_twist.setTwist(n);
}
bool CAX25Demodulator::isDCD()
{
if (m_pllJitter <= (SAMPLES_PER_SYMBOL * 0.03F))
m_pllDCD = true;
else if (m_pllJitter >= (SAMPLES_PER_SYMBOL * 0.15F))
m_pllDCD = false;
return m_pllDCD;
}
float32_t CAX25Demodulator::iir(float32_t input)
{
for (int8_t i = int8_t(PLL_IIR_SIZE) - 1; i != 0; i--)
m_iirHistory[i] = m_iirHistory[i - 1];
m_iirHistory[0] = input;
for (uint8_t i = 1U; i < PLL_IIR_SIZE; i++)
m_iirHistory[0] -= PLL_LOCK_A[i] * m_iirHistory[i];
float32_t result = 0.0F;
for (uint8_t i = 0U; i < PLL_IIR_SIZE; i++)
result += PLL_LOCK_B[i] * m_iirHistory[i];
return result;
}

73
AX25Demodulator.h Normal file
View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(AX25Demodulator_H)
#define AX25Demodulator_H
#include "Config.h"
#include "AX25Frame.h"
#include "AX25Twist.h"
enum AX25_STATE {
AX25_IDLE,
AX25_SYNC,
AX25_RECEIVE
};
class CAX25Demodulator {
public:
CAX25Demodulator(int8_t n);
bool process(q15_t* samples, uint8_t length, CAX25Frame& frame);
void setTwist(int8_t n);
bool isDCD();
private:
CAX25Frame m_frame;
CAX25Twist m_twist;
arm_fir_instance_q15 m_lpfFilter;
q15_t m_lpfState[70U]; // NoTaps + BlockSize - 1, 48 + 20 - 1 plus some spare
bool* m_delayLine;
uint16_t m_delayPos;
bool m_nrziState;
arm_fir_instance_f32 m_pllFilter;
float32_t m_pllState[20U]; // NoTaps + BlockSize - 1, 7 + 1 - 1 plus some spare
bool m_pllLast;
uint8_t m_pllBits;
float32_t m_pllCount;
float32_t m_pllJitter;
bool m_pllDCD;
float32_t m_iirHistory[5U];
uint16_t m_hdlcOnes;
bool m_hdlcFlag;
uint16_t m_hdlcBuffer;
uint16_t m_hdlcBits;
AX25_STATE m_hdlcState;
bool delay(bool b);
bool NRZI(bool b);
bool PLL(bool b);
bool HDLC(bool b);
float32_t iir(float32_t input);
};
#endif

122
AX25Frame.cpp Normal file
View File

@ -0,0 +1,122 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "AX25Frame.h"
const uint16_t CCITT_TABLE[] = {
0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78 };
CAX25Frame::CAX25Frame(const uint8_t* data, uint16_t length) :
m_data(),
m_length(0U),
m_fcs(0U)
{
for (uint16_t i = 0U; i < length && i < (AX25_MAX_PACKET_LEN - 2U); i++)
m_data[m_length++] = data[i];
}
CAX25Frame::CAX25Frame() :
m_data(),
m_length(0U),
m_fcs(0U)
{
}
bool CAX25Frame::append(uint16_t c)
{
if (m_length == AX25_MAX_PACKET_LEN)
return false;
m_data[m_length++] = uint8_t(c);
return true;
}
bool CAX25Frame::checkCRC()
{
union {
uint16_t crc16;
uint8_t crc8[2U];
};
crc16 = 0xFFFFU;
for (uint16_t i = 0U; i < (m_length - 2U); i++)
crc16 = uint16_t(crc8[1U]) ^ CCITT_TABLE[crc8[0U] ^ m_data[i]];
crc16 = ~crc16;
if (crc8[0U] == m_data[m_length - 2U] && crc8[1U] == m_data[m_length - 1U]) {
m_fcs = crc16;
return true;
} else {
return false;
}
}
void CAX25Frame::addCRC()
{
union {
uint16_t crc16;
uint8_t crc8[2U];
};
crc16 = 0xFFFFU;
for (uint16_t i = 0U; i < m_length; i++)
crc16 = uint16_t(crc8[1U]) ^ CCITT_TABLE[crc8[0U] ^ m_data[i]];
crc16 = ~crc16;
m_fcs = crc16;
m_data[m_length++] = crc8[0U];
m_data[m_length++] = crc8[1U];
}

43
AX25Frame.h Normal file
View File

@ -0,0 +1,43 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(AX25Frame_H)
#define AX25Frame_H
#include "Config.h"
const uint16_t AX25_MAX_PACKET_LEN = 300U;
class CAX25Frame {
public:
CAX25Frame(const uint8_t* data, uint16_t length);
CAX25Frame();
bool append(uint16_t c);
bool checkCRC();
void addCRC();
uint8_t m_data[AX25_MAX_PACKET_LEN];
uint16_t m_length;
uint16_t m_fcs;
};
#endif

205
AX25RX.cpp Normal file
View File

@ -0,0 +1,205 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "AX25RX.h"
/*
* Generated with Scipy Filter, 152 coefficients, 1100-2300Hz bandpass,
* Hann window, starting and ending 0 value coefficients removed.
*
* np.array(
* firwin2(152,
* [
* 0.0,
* 1000.0/(sample_rate/2),
* 1100.0/(sample_rate/2),
* 2350.0/(sample_rate/2),
* 2500.0/(sample_rate/2),
* 1.0
* ],
* [0,0,1,1,0,0],
* antisymmetric = False,
* window='hann') * 32768,
* dtype=int)[10:-10]
*/
const uint32_t FILTER_LEN = 130U;
q15_t FILTER_COEFFS[] = {
5, 12, 18, 21, 19, 11, -2, -15, -25, -27,
-21, -11, -3, -5, -19, -43, -69, -83, -73, -35,
27, 98, 155, 180, 163, 109, 39, -20, -45, -26,
23, 74, 89, 39, -81, -247, -407, -501, -480, -334,
-92, 175, 388, 479, 429, 275, 99, 5, 68, 298,
626, 913, 994, 740, 115, -791, -1770, -2544, -2847, -2509,
-1527, -76, 1518, 2875, 3653, 3653, 2875, 1518, -76, -1527,
-2509, -2847, -2544, -1770, -791, 115, 740, 994, 913, 626,
298, 68, 5, 99, 275, 429, 479, 388, 175, -92,
-334, -480, -501, -407, -247, -81, 39, 89, 74, 23,
-26, -45, -20, 39, 109, 163, 180, 155, 98, 27,
-35, -73, -83, -69, -43, -19, -5, -3, -11, -21,
-27, -25, -15, -2, 11, 19, 21, 18, 12, 5
};
CAX25RX::CAX25RX() :
m_filter(),
m_state(),
m_demod1(3),
m_demod2(6),
m_demod3(9),
m_lastFCS(0U),
m_count(0U),
m_slotTime(30U),
m_slotCount(0U),
m_pPersist(128U),
m_dcd(false),
m_canTX(false),
m_x(1U),
m_a(0xB7U),
m_b(0x73U),
m_c(0xF6U)
{
m_filter.numTaps = FILTER_LEN;
m_filter.pState = m_state;
m_filter.pCoeffs = FILTER_COEFFS;
initRand();
}
void CAX25RX::samples(q15_t* samples, uint8_t length)
{
q15_t output[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_filter, samples, output, RX_BLOCK_SIZE);
m_count++;
CAX25Frame frame;
bool ret = m_demod1.process(output, length, frame);
if (ret) {
if (frame.m_fcs != m_lastFCS || m_count > 2U) {
m_lastFCS = frame.m_fcs;
m_count = 0U;
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
}
DEBUG1("Decoder 1 reported");
}
ret = m_demod2.process(output, length, frame);
if (ret) {
if (frame.m_fcs != m_lastFCS || m_count > 2U) {
m_lastFCS = frame.m_fcs;
m_count = 0U;
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
}
DEBUG1("Decoder 2 reported");
}
ret = m_demod3.process(output, length, frame);
if (ret) {
if (frame.m_fcs != m_lastFCS || m_count > 2U) {
m_lastFCS = frame.m_fcs;
m_count = 0U;
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
}
DEBUG1("Decoder 3 reported");
}
m_slotCount += RX_BLOCK_SIZE;
if (m_slotCount >= m_slotTime) {
m_slotCount = 0U;
bool dcd1 = m_demod1.isDCD();
bool dcd2 = m_demod2.isDCD();
bool dcd3 = m_demod3.isDCD();
if (dcd1 || dcd2 || dcd3) {
if (!m_dcd) {
io.setDecode(true);
io.setADCDetection(true);
m_dcd = true;
}
m_canTX = false;
} else {
if (m_dcd) {
io.setDecode(false);
io.setADCDetection(false);
m_dcd = false;
}
m_canTX = m_pPersist >= rand();
}
}
}
bool CAX25RX::canTX() const
{
return m_canTX;
}
void CAX25RX::setParams(int8_t twist, uint8_t slotTime, uint8_t pPersist)
{
m_demod1.setTwist(twist - 3);
m_demod2.setTwist(twist);
m_demod3.setTwist(twist + 3);
m_slotTime = slotTime * 240U; // Slot time in samples
m_pPersist = pPersist;
}
// Taken from https://www.electro-tech-online.com/threads/ultra-fast-pseudorandom-number-generator-for-8-bit.124249/
//X ABC Algorithm Random Number Generator for 8-Bit Devices:
//This is a small PRNG, experimentally verified to have at least a 50 million byte period
//by generating 50 million bytes and observing that there were no overapping sequences and repeats.
//This generator passes serial correlation, entropy , Monte Carlo Pi value, arithmetic mean,
//And many other statistical tests. This generator may have a period of up to 2^32, but this has
//not been verified.
//
// By XORing 3 bytes into the a,b, and c registers, you can add in entropy from
//an external source easily.
//
//This generator is free to use, but is not suitable for cryptography due to its short period(by //cryptographic standards) and simple construction. No attempt was made to make this generator
// suitable for cryptographic use.
//
//Due to the use of a constant counter, the generator should be resistant to latching up.
//A significant performance gain is had in that the x variable is only ever incremented.
//
//Only 4 bytes of ram are needed for the internal state, and generating a byte requires 3 XORs , //2 ADDs, one bit shift right , and one increment. Difficult or slow operations like multiply, etc
//were avoided for maximum speed on ultra low power devices.
void CAX25RX::initRand() //Can also be used to seed the rng with more entropy during use.
{
m_a = (m_a ^ m_c ^ m_x);
m_b = (m_b + m_a);
m_c = (m_c + (m_b >> 1) ^ m_a);
}
uint8_t CAX25RX::rand()
{
m_x++; //x is incremented every round and is not affected by any other variable
m_a = (m_a ^ m_c ^ m_x); //note the mix of addition and XOR
m_b = (m_b + m_a); //And the use of very few instructions
m_c = (m_c + (m_b >> 1) ^ m_a); //the right shift is to ensure that high-order bits from b can affect
return uint8_t(m_c); //low order bits of other variables
}

59
AX25RX.h Normal file
View File

@ -0,0 +1,59 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(AX25RX_H)
#define AX25RX_H
#include "Config.h"
#include "AX25Demodulator.h"
class CAX25RX {
public:
CAX25RX();
void samples(q15_t* samples, uint8_t length);
void setParams(int8_t twist, uint8_t slotTime, uint8_t pPersist);
bool canTX() const;
private:
arm_fir_instance_q15 m_filter;
q15_t m_state[160U]; // NoTaps + BlockSize - 1, 130 + 20 - 1 plus some spare
CAX25Demodulator m_demod1;
CAX25Demodulator m_demod2;
CAX25Demodulator m_demod3;
uint16_t m_lastFCS;
uint32_t m_count;
uint32_t m_slotTime;
uint32_t m_slotCount;
uint8_t m_pPersist;
bool m_dcd;
bool m_canTX;
uint8_t m_x;
uint8_t m_a;
uint8_t m_b;
uint8_t m_c;
void initRand();
uint8_t rand();
};
#endif

186
AX25TX.cpp Normal file
View File

@ -0,0 +1,186 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "AX25TX.h"
#include "AX25Defines.h"
#include "AX25Frame.h"
const uint8_t START_FLAG[] = { AX25_FRAME_START };
const uint8_t END_FLAG[] = { AX25_FRAME_END };
const uint8_t BIT_MASK_TABLE1[] = { 0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02U, 0x01U };
#define WRITE_BIT1(p,i,b) p[(i)>>3] = (b) ? (p[(i)>>3] | BIT_MASK_TABLE1[(i)&7]) : (p[(i)>>3] & ~BIT_MASK_TABLE1[(i)&7])
#define READ_BIT1(p,i) (p[(i)>>3] & BIT_MASK_TABLE1[(i)&7])
const uint8_t BIT_MASK_TABLE2[] = { 0x01U, 0x02U, 0x04U, 0x08U, 0x10U, 0x20U, 0x40U, 0x80U };
#define WRITE_BIT2(p,i,b) p[(i)>>3] = (b) ? (p[(i)>>3] | BIT_MASK_TABLE2[(i)&7]) : (p[(i)>>3] & ~BIT_MASK_TABLE2[(i)&7])
#define READ_BIT2(p,i) (p[(i)>>3] & BIT_MASK_TABLE2[(i)&7])
const uint16_t AUDIO_TABLE_LEN = 120U;
const q15_t AUDIO_TABLE_DATA[] = {
0, 214, 428, 641, 851, 1060, 1265, 1468, 1666, 1859, 2048, 2230, 2407, 2577, 2740, 2896, 3043, 3182, 3313, 3434, 3546, 3649,
3741, 3823, 3895, 3955, 4006, 4045, 4073, 4089, 4095, 4089, 4073, 4045, 4006, 3955, 3895, 3823, 3741, 3649, 3546, 3434, 3313,
3182, 3043, 2896, 2740, 2577, 2407, 2230, 2048, 1859, 1666, 1468, 1265, 1060, 851, 641, 428, 214, 0, -214, -428, -641, -851,
-1060, -1265, -1468, -1666, -1859, -2047, -2230, -2407, -2577, -2740, -2896, -3043, -3182, -3313, -3434, -3546, -3649, -3741,
-3823, -3895, -3955, -4006, -4045, -4073, -4089, -4095, -4089, -4073, -4045, -4006, -3955, -3895, -3823, -3741, -3649, -3546,
-3434, -3313, -3182, -3043, -2896, -2740, -2577, -2407, -2230, -2047, -1859, -1666, -1468, -1265, -1060, -851, -641, -428, -214
};
CAX25TX::CAX25TX() :
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U),
m_txDelay(360U),
m_tablePtr(0U),
m_nrzi(false)
{
}
void CAX25TX::process()
{
if (m_poLen == 0U)
return;
if (!m_duplex) {
if (m_poPtr == 0U) {
bool tx = ax25RX.canTX();
if (!tx)
return;
}
}
uint16_t space = io.getSpace();
while (space > AX25_RADIO_SYMBOL_LENGTH) {
bool b = READ_BIT1(m_poBuffer, m_poPtr) != 0U;
m_poPtr++;
writeBit(b);
space -= AX25_RADIO_SYMBOL_LENGTH;
if (m_poPtr >= m_poLen) {
m_poPtr = 0U;
m_poLen = 0U;
return;
}
}
}
uint8_t CAX25TX::writeData(const uint8_t* data, uint16_t length)
{
CAX25Frame frame(data, length);
frame.addCRC();
m_poLen = 0U;
m_poPtr = 0U;
m_nrzi = false;
m_tablePtr = 0U;
// Add TX delay
for (uint16_t i = 0U; i < m_txDelay; i++, m_poLen++) {
bool preamble = NRZI(false);
WRITE_BIT1(m_poBuffer, m_poLen, preamble);
}
// Add the Start Flag
for (uint16_t i = 0U; i < 8U; i++, m_poLen++) {
bool b1 = READ_BIT1(START_FLAG, i) != 0U;
bool b2 = NRZI(b1);
WRITE_BIT1(m_poBuffer, m_poLen, b2);
}
uint8_t ones = 0U;
for (uint16_t i = 0U; i < (frame.m_length * 8U); i++) {
bool b1 = READ_BIT2(frame.m_data, i) != 0U;
bool b2 = NRZI(b1);
WRITE_BIT1(m_poBuffer, m_poLen, b2);
m_poLen++;
if (b1) {
ones++;
if (ones == AX25_MAX_ONES) {
// Bit stuffing
bool b = NRZI(false);
WRITE_BIT1(m_poBuffer, m_poLen, b);
m_poLen++;
ones = 0U;
}
} else {
ones = 0U;
}
}
// Add the End Flag
for (uint16_t i = 0U; i < 8U; i++, m_poLen++) {
bool b1 = READ_BIT1(END_FLAG, i) != 0U;
bool b2 = NRZI(b1);
WRITE_BIT1(m_poBuffer, m_poLen, b2);
}
return 0U;
}
void CAX25TX::writeBit(bool b)
{
q15_t buffer[AX25_RADIO_SYMBOL_LENGTH];
for (uint8_t i = 0U; i < AX25_RADIO_SYMBOL_LENGTH; i++) {
q15_t value = AUDIO_TABLE_DATA[m_tablePtr];
if (b) {
// De-emphasise the lower frequency by 6dB
value >>= 2;
m_tablePtr += 6U;
} else {
m_tablePtr += 11U;
}
buffer[i] = value;
if (m_tablePtr >= AUDIO_TABLE_LEN)
m_tablePtr -= AUDIO_TABLE_LEN;
}
io.write(STATE_AX25, buffer, AX25_RADIO_SYMBOL_LENGTH);
}
void CAX25TX::setTXDelay(uint8_t delay)
{
m_txDelay = delay * 12U;
}
uint8_t CAX25TX::getSpace() const
{
return m_poLen == 0U ? 255U : 0U;
}
bool CAX25TX::NRZI(bool b)
{
if (!b)
m_nrzi = !m_nrzi;
return m_nrzi;
}

49
AX25TX.h Normal file
View File

@ -0,0 +1,49 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(AX25TX_H)
#define AX25TX_H
#include "Config.h"
class CAX25TX {
public:
CAX25TX();
uint8_t writeData(const uint8_t* data, uint16_t length);
void process();
void setTXDelay(uint8_t delay);
uint8_t getSpace() const;
private:
uint8_t m_poBuffer[600U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint16_t m_txDelay;
uint16_t m_tablePtr;
bool m_nrzi;
void writeBit(bool b);
bool NRZI(bool b);
};
#endif

311
AX25Twist.cpp Normal file
View File

@ -0,0 +1,311 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "AX25Twist.h"
// 1200Hz = -12dB, 2200Hz = 0dB; 3381Hz cutoff; cosine.
q15_t dB12[] = {
176,
-812,
-3916,
-7586,
23536,
-7586,
-3916,
-812,
176
};
// 1200Hz = -11dB, 2200Hz = 0dB; 3258Hz cutoff; cosine.
q15_t dB11[] = {
121,
-957,
-3959,
-7383,
23871,
-7383,
-3959,
-957,
121
};
// 1200Hz = -10dB, 2200Hz = 0dB; 3118Hz cutoff; cosine.
q15_t dB10[] = {
56,
-1110,
-3987,
-7141,
24254,
-7141,
-3987,
-1110,
56
};
// 1200Hz = -9dB, 2200Hz = 0dB; 2959Hz cutoff; cosine.
q15_t dB9[] = {
-19,
-1268,
-3994,
-6856,
24688,
-6856,
-3994,
-1268,
-19
};
// 1200Hz = -8dB, 2200Hz = 0dB; 2778Hz cutoff; cosine.
q15_t dB8[] = {
-104,
-1424,
-3968,
-6516,
25182,
-6516,
-3968,
-1424,
-104
};
// 1200Hz = -7dB, 2200Hz = 0dB; 2573Hz cutoff; cosine.
q15_t dB7[] = {
-196,
-1565,
-3896,
-6114,
25742,
-6114,
-3896,
-1565,
-196
};
// 1200Hz = -6dB, 2200Hz = 0dB; 2343Hz cutoff; cosine.
q15_t dB6[] = {
-288,
-1676,
-3761,
-5642,
26370,
-5642,
-3761,
-1676,
-288
};
// 1200Hz = -5dB, 2200Hz = 0dB; 2085Hz cutoff; cosine.
q15_t dB5[] = {
-370,
-1735,
-3545,
-5088,
27075,
-5088,
-3545,
-1735,
-370
};
// 1200Hz = -4dB, 2200Hz = 0dB; 1790Hz cutoff; cosine.
q15_t dB4[] = {
-432,
-1715,
-3220,
-4427,
27880,
-4427,
-3220,
-1715,
-432
};
// 1200Hz = -3dB, 2200Hz = 0dB; 1456Hz cutoff; cosine.
q15_t dB3[] = {
-452,
-1582,
-2759,
-3646,
28792,
-3646,
-2759,
-1582,
-452
};
// 1200Hz = -2dB, 2200Hz = 0dB; 1070Hz cutoff; cosine.
q15_t dB2[] = {
-408,
-1295,
-2123,
-2710,
29846,
-2710,
-2123,
-1295,
-408
};
// 1200Hz = -1dB, 2200Hz = 0dB; 605Hz cutoff; cosine.
q15_t dB1[] = {
-268,
-795,
-1244,
-1546,
31116,
-1546,
-1244,
-795,
-268
};
q15_t dB0[] = {
0,
0,
0,
0,
32767,
0,
0,
0,
0,
};
// 1200Hz = 0dB, 2200Hz = -1dB; 4130Hz cutoff; cosine.
q15_t dB_1[] = {
-419,
-177,
3316,
8650,
11278,
8650,
3316,
-177,
-419
};
// 1200Hz = 0dB, 2200Hz = -2dB; 3190Hz cutoff; cosine.
q15_t dB_2[] = {
-90,
1033,
3975,
7267,
8711,
7267,
3975,
1033,
-90
};
// 1200Hz = 0dB, 2200Hz = -3dB; 2330Hz cutoff; cosine.
q15_t dB_3[] = {
292,
1680,
3752,
5615,
6362,
5615,
3752,
1680,
292
};
// 1200Hz = 0dB, 2200Hz = -4dB; 2657Hz cutoff; boxcar.
q15_t dB_4[] = {
917,
3024,
5131,
6684,
7255,
6684,
5131,
3024,
917
};
// 1200Hz = 0dB, 2200Hz = -5dB; 2360Hz cutoff; boxcar.
q15_t dB_5[] = {
1620,
3339,
4925,
6042,
6444,
6042,
4925,
3339,
1620
};
// 1200Hz = 0dB, 2200Hz = -6dB; 2067Hz cutoff; boxcar.
q15_t dB_6[] = {
2161,
3472,
4605,
5373,
5644,
5373,
4605,
3472,
2161
};
q15_t* coeffs[] = {
dB12,
dB11,
dB10,
dB9,
dB8,
dB7,
dB6,
dB5,
dB4,
dB3,
dB2,
dB1,
dB0,
dB_1,
dB_2,
dB_3,
dB_4,
dB_5,
dB_6
};
CAX25Twist::CAX25Twist(int8_t n) :
m_filter(),
m_state()
{
setTwist(n);
}
void CAX25Twist::process(q15_t* in, q15_t* out, uint8_t length)
{
::arm_fir_fast_q15(&m_filter, in, out, length);
}
void CAX25Twist::setTwist(int8_t n)
{
uint8_t twist = uint8_t(n + 6);
m_filter.numTaps = 9;
m_filter.pState = m_state;
m_filter.pCoeffs = coeffs[twist];
}

39
AX25Twist.h Normal file
View File

@ -0,0 +1,39 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(AX25Twist_H)
#define AX25Twist_H
#include "Config.h"
class CAX25Twist {
public:
CAX25Twist(int8_t n);
void process(q15_t* in, q15_t* out, uint8_t length);
void setTwist(int8_t n);
private:
arm_fir_instance_q15 m_filter;
q15_t m_state[40U]; // NoTaps + BlockSize - 1, 9 + 20 - 1 plus some spare
};
#endif

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX * Copyright (C) 2009-2017,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -125,7 +125,7 @@ void CCWIdTX::process()
} }
} }
uint8_t CCWIdTX::write(const uint8_t* data, uint8_t length) uint8_t CCWIdTX::write(const uint8_t* data, uint16_t length)
{ {
::memset(m_poBuffer, 0x00U, 1000U * sizeof(uint8_t)); ::memset(m_poBuffer, 0x00U, 1000U * sizeof(uint8_t));

View File

@ -1,6 +1,6 @@
/* /*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX * Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016,2020 by Colin Durbridge G4EML
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -28,7 +28,7 @@ public:
void process(); void process();
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
void reset(); void reset();

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX * Copyright (C) 2009-2015,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -208,7 +208,7 @@ void CCalDMR::dmrdmo1k()
} }
} }
uint8_t CCalDMR::write(const uint8_t* data, uint8_t length) uint8_t CCalDMR::write(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX * Copyright (C) 2009-2015,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -41,7 +41,7 @@ public:
void createData1k(uint8_t n); void createData1k(uint8_t n);
void createDataDMO1k(uint8_t n); void createDataDMO1k(uint8_t n);
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
private: private:
bool m_transmit; bool m_transmit;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX * Copyright (C) 2009-2016,2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -162,7 +162,7 @@ void CCalDStarTX::process()
m_count = (m_count + 1U) % (30U * 21U); m_count = (m_count + 1U) % (30U * 21U);
} }
uint8_t CCalDStarTX::write(const uint8_t* data, uint8_t length) uint8_t CCalDStarTX::write(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX * Copyright (C) 2015,2016,2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -26,7 +26,7 @@ class CCalDStarTX {
public: public:
CCalDStarTX(); CCalDStarTX();
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
void process(); void process();

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX * Copyright (C) 2009-2015,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* Copyright (C) 2020 by Phil Taylor M0VSE * Copyright (C) 2020 by Phil Taylor M0VSE
* *
@ -52,7 +52,7 @@ void CCalFM::process()
{ {
const TONE_TABLE* entry = NULL; const TONE_TABLE* entry = NULL;
if (m_modemState!=m_lastState) if (m_modemState != m_lastState)
{ {
switch (m_modemState) { switch (m_modemState) {
case STATE_FMCAL10K: case STATE_FMCAL10K:
@ -116,7 +116,7 @@ void CCalFM::process()
} }
uint8_t CCalFM::write(const uint8_t* data, uint8_t length) uint8_t CCalFM::write(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX * Copyright (C) 2009-2015,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* Copyright (C) 2020 by Phil Taylor M0VSE * Copyright (C) 2020 by Phil Taylor M0VSE
* *
@ -35,7 +35,7 @@ public:
void fm25kcal(); void fm25kcal();
void fm30kcal(); void fm30kcal();
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
private: private:
uint16_t m_frequency; uint16_t m_frequency;

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2018 by Andy Uribe CA6JAU * Copyright (C) 2018 by Andy Uribe CA6JAU
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -79,7 +80,7 @@ void CCalNXDN::process()
} }
} }
uint8_t CCalNXDN::write(const uint8_t* data, uint8_t length) uint8_t CCalNXDN::write(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2018 by Andy Uribe CA6JAU * Copyright (C) 2018 by Andy Uribe CA6JAU
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -32,7 +33,7 @@ public:
void process(); void process();
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
private: private:
bool m_transmit; bool m_transmit;

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2018 by Andy Uribe CA6JAU * Copyright (C) 2018 by Andy Uribe CA6JAU
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -82,7 +83,7 @@ void CCalP25::process()
} }
} }
uint8_t CCalP25::write(const uint8_t* data, uint8_t length) uint8_t CCalP25::write(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2018 by Andy Uribe CA6JAU * Copyright (C) 2018 by Andy Uribe CA6JAU
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -34,7 +35,7 @@ public:
void process(); void process();
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
private: private:
bool m_transmit; bool m_transmit;

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2019 by Florian Wolters DF2ET * Copyright (C) 2019 by Florian Wolters DF2ET
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -38,7 +39,7 @@ void CCalPOCSAG::process()
pocsagTX.writeByte(0xAAU); pocsagTX.writeByte(0xAAU);
} }
uint8_t CCalPOCSAG::write(const uint8_t* data, uint8_t length) uint8_t CCalPOCSAG::write(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2019 by Florian Wolters DF2ET * Copyright (C) 2019 by Florian Wolters DF2ET
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -32,7 +33,7 @@ public:
void process(); void process();
uint8_t write(const uint8_t* data, uint8_t length); uint8_t write(const uint8_t* data, uint16_t length);
private: private:
POCSAGCAL m_state; POCSAGCAL m_state;

View File

@ -35,8 +35,16 @@
// For 19.2 MHz // For 19.2 MHz
// #define EXTERNAL_OSC 19200000 // #define EXTERNAL_OSC 19200000
// Use a higher baudrate for host communication. Required for FM network !
#define SERIAL_SPEED 115200 //suitable for most older boards (Arduino, Due STM32F1_POG etc). External FM will NOT work with this !
// #define SERIAL_SPEED 230400 // Only works on newer board M4, M7, Teensy. External FM might work with this
// #define SERIAL_SPEED 460800 // Only works on newer board M4, M7, Teensy. External FM should work with this
// Allow the use of the COS line to lockout the modem
// #define USE_COS_AS_LOCKOUT
// Use pins to output the current mode via LEDs // Use pins to output the current mode via LEDs
// #define MODE_LEDS #define MODE_LEDS
// For the original Arduino Due pin layout // For the original Arduino Due pin layout
// #define ARDUINO_DUE_PAPA // #define ARDUINO_DUE_PAPA
@ -79,12 +87,13 @@
// #define USE_ALTERNATE_NXDN_LEDS // #define USE_ALTERNATE_NXDN_LEDS
// Use the D-Star and P25 LEDs for M17 // Use the D-Star and P25 LEDs for M17
// #define USE_ALTERNATE_M17_LEDS #define USE_ALTERNATE_M17_LEDS
// Use the D-Star and DMR LEDs for POCSAG // Use the D-Star and DMR LEDs for POCSAG
// #define USE_ALTERNATE_POCSAG_LEDS #define USE_ALTERNATE_POCSAG_LEDS
// Use the D-Star and YSF LEDs for FM // Use the D-Star and YSF LEDs for FM
#define USE_ALTERNATE_FM_LEDS #define USE_ALTERNATE_FM_LEDS
#endif #endif

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX * Copyright (C) 2009-2017,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* Copyright (C) 2017 by Andy Uribe CA6JAU * Copyright (C) 2017 by Andy Uribe CA6JAU
* *
@ -74,7 +74,7 @@ void CDMRDMOTX::process()
m_poLen = m_txDelay; m_poLen = m_txDelay;
} else { } else {
for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++) for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++)
m_poBuffer[i] = m_fifo.get(); m_fifo.get(m_poBuffer[i]);
for (unsigned int i = 0U; i < 39U; i++) for (unsigned int i = 0U; i < 39U; i++)
m_poBuffer[i + DMR_FRAME_LENGTH_BYTES] = PR_FILL[i]; m_poBuffer[i + DMR_FRAME_LENGTH_BYTES] = PR_FILL[i];
@ -104,7 +104,7 @@ void CDMRDMOTX::process()
} }
} }
uint8_t CDMRDMOTX::writeData(const uint8_t* data, uint8_t length) uint8_t CDMRDMOTX::writeData(const uint8_t* data, uint16_t length)
{ {
if (length != (DMR_FRAME_LENGTH_BYTES + 1U)) if (length != (DMR_FRAME_LENGTH_BYTES + 1U))
return 4U; return 4U;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX * Copyright (C) 2015,2016,2017,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -23,13 +23,13 @@
#include "Config.h" #include "Config.h"
#include "DMRDefines.h" #include "DMRDefines.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CDMRDMOTX { class CDMRDMOTX {
public: public:
CDMRDMOTX(); CDMRDMOTX();
uint8_t writeData(const uint8_t* data, uint8_t length); uint8_t writeData(const uint8_t* data, uint16_t length);
void process(); void process();
@ -38,7 +38,7 @@ public:
uint8_t getSpace() const; uint8_t getSpace() const;
private: private:
CSerialRB m_fifo; CRingBuffer<uint8_t> m_fifo;
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare
uint8_t m_poBuffer[1200U]; uint8_t m_poBuffer[1200U];

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX * Copyright (C) 2009-2017,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* Copyright (C) 2017 by Andy Uribe CA6JAU * Copyright (C) 2017 by Andy Uribe CA6JAU
* *
@ -144,7 +144,7 @@ void CDMRTX::process()
} }
} }
uint8_t CDMRTX::writeData1(const uint8_t* data, uint8_t length) uint8_t CDMRTX::writeData1(const uint8_t* data, uint16_t length)
{ {
if (length != (DMR_FRAME_LENGTH_BYTES + 1U)) if (length != (DMR_FRAME_LENGTH_BYTES + 1U))
return 4U; return 4U;
@ -168,7 +168,7 @@ uint8_t CDMRTX::writeData1(const uint8_t* data, uint8_t length)
return 0U; return 0U;
} }
uint8_t CDMRTX::writeData2(const uint8_t* data, uint8_t length) uint8_t CDMRTX::writeData2(const uint8_t* data, uint16_t length)
{ {
if (length != (DMR_FRAME_LENGTH_BYTES + 1U)) if (length != (DMR_FRAME_LENGTH_BYTES + 1U))
return 4U; return 4U;
@ -192,7 +192,7 @@ uint8_t CDMRTX::writeData2(const uint8_t* data, uint8_t length)
return 0U; return 0U;
} }
uint8_t CDMRTX::writeShortLC(const uint8_t* data, uint8_t length) uint8_t CDMRTX::writeShortLC(const uint8_t* data, uint16_t length)
{ {
if (length != 9U) if (length != 9U)
return 4U; return 4U;
@ -208,7 +208,7 @@ uint8_t CDMRTX::writeShortLC(const uint8_t* data, uint8_t length)
return 0U; return 0U;
} }
uint8_t CDMRTX::writeAbort(const uint8_t* data, uint8_t length) uint8_t CDMRTX::writeAbort(const uint8_t* data, uint16_t length)
{ {
if (length != 1U) if (length != 1U)
return 4U; return 4U;
@ -293,7 +293,7 @@ void CDMRTX::createData(uint8_t slotIndex)
{ {
if (m_fifo[slotIndex].getData() >= DMR_FRAME_LENGTH_BYTES && m_frameCount >= STARTUP_COUNT && m_abortCount[slotIndex] >= ABORT_COUNT) { if (m_fifo[slotIndex].getData() >= DMR_FRAME_LENGTH_BYTES && m_frameCount >= STARTUP_COUNT && m_abortCount[slotIndex] >= ABORT_COUNT) {
for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++) { for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++) {
m_poBuffer[i] = m_fifo[slotIndex].get(); m_fifo[slotIndex].get(m_poBuffer[i]);
m_markBuffer[i] = MARK_NONE; m_markBuffer[i] = MARK_NONE;
} }
} else { } else {

14
DMRTX.h
View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX * Copyright (C) 2015,2016,2017,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML * Copyright (C) 2016 by Colin Durbridge G4EML
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -23,7 +23,7 @@
#include "Config.h" #include "Config.h"
#include "DMRDefines.h" #include "DMRDefines.h"
#include "SerialRB.h" #include "RingBuffer.h"
enum DMRTXSTATE { enum DMRTXSTATE {
DMRTXSTATE_IDLE, DMRTXSTATE_IDLE,
@ -38,11 +38,11 @@ class CDMRTX {
public: public:
CDMRTX(); CDMRTX();
uint8_t writeData1(const uint8_t* data, uint8_t length); uint8_t writeData1(const uint8_t* data, uint16_t length);
uint8_t writeData2(const uint8_t* data, uint8_t length); uint8_t writeData2(const uint8_t* data, uint16_t length);
uint8_t writeShortLC(const uint8_t* data, uint8_t length); uint8_t writeShortLC(const uint8_t* data, uint16_t length);
uint8_t writeAbort(const uint8_t* data, uint8_t length); uint8_t writeAbort(const uint8_t* data, uint16_t length);
void setStart(bool start); void setStart(bool start);
void setCal(bool start); void setCal(bool start);
@ -59,7 +59,7 @@ public:
void setColorCode(uint8_t colorCode); void setColorCode(uint8_t colorCode);
private: private:
CSerialRB m_fifo[2U]; CRingBuffer<uint8_t> m_fifo[2U];
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare
DMRTXSTATE m_state; DMRTXSTATE m_state;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX * Copyright (C) 2009-2017,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2017 by Andy Uribe CA6JAU * Copyright (C) 2017 by Andy Uribe CA6JAU
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -216,12 +216,13 @@ void CDStarTX::process()
for (uint16_t i = 0U; i < m_txDelay; i++) for (uint16_t i = 0U; i < m_txDelay; i++)
m_poBuffer[m_poLen++] = BIT_SYNC; m_poBuffer[m_poLen++] = BIT_SYNC;
} else { } else {
uint8_t dummy;
// Pop the type byte off // Pop the type byte off
m_buffer.get(); m_buffer.get(dummy);
uint8_t header[DSTAR_HEADER_LENGTH_BYTES]; uint8_t header[DSTAR_HEADER_LENGTH_BYTES];
for (uint8_t i = 0U; i < DSTAR_HEADER_LENGTH_BYTES; i++) for (uint8_t i = 0U; i < DSTAR_HEADER_LENGTH_BYTES; i++)
header[i] = m_buffer.get(); m_buffer.get(header[i]);
uint8_t buffer[86U]; uint8_t buffer[86U];
txHeader(header, buffer + 2U); txHeader(header, buffer + 2U);
@ -239,17 +240,19 @@ void CDStarTX::process()
if (type == DSTAR_DATA && m_poLen == 0U) { if (type == DSTAR_DATA && m_poLen == 0U) {
// Pop the type byte off // Pop the type byte off
m_buffer.get(); uint8_t dummy;
m_buffer.get(dummy);
for (uint8_t i = 0U; i < DSTAR_DATA_LENGTH_BYTES; i++) for (uint8_t i = 0U; i < DSTAR_DATA_LENGTH_BYTES; i++)
m_poBuffer[m_poLen++] = m_buffer.get(); m_buffer.get(m_poBuffer[m_poLen++]);
m_poPtr = 0U; m_poPtr = 0U;
} }
if (type == DSTAR_EOT && m_poLen == 0U) { if (type == DSTAR_EOT && m_poLen == 0U) {
// Pop the type byte off // Pop the type byte off
m_buffer.get(); uint8_t dummy;
m_buffer.get(dummy);
for (uint8_t j = 0U; j < 3U; j++) { for (uint8_t j = 0U; j < 3U; j++) {
for (uint8_t i = 0U; i < DSTAR_EOT_LENGTH_BYTES; i++) for (uint8_t i = 0U; i < DSTAR_EOT_LENGTH_BYTES; i++)
@ -277,7 +280,7 @@ void CDStarTX::process()
} }
} }
uint8_t CDStarTX::writeHeader(const uint8_t* header, uint8_t length) uint8_t CDStarTX::writeHeader(const uint8_t* header, uint16_t length)
{ {
if (length != DSTAR_HEADER_LENGTH_BYTES) if (length != DSTAR_HEADER_LENGTH_BYTES)
return 4U; return 4U;
@ -296,7 +299,7 @@ uint8_t CDStarTX::writeHeader(const uint8_t* header, uint8_t length)
return 0U; return 0U;
} }
uint8_t CDStarTX::writeData(const uint8_t* data, uint8_t length) uint8_t CDStarTX::writeData(const uint8_t* data, uint16_t length)
{ {
if (length != DSTAR_DATA_LENGTH_BYTES) if (length != DSTAR_DATA_LENGTH_BYTES)
return 4U; return 4U;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX * Copyright (C) 2015,2016,2017,2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -21,14 +21,14 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CDStarTX { class CDStarTX {
public: public:
CDStarTX(); CDStarTX();
uint8_t writeHeader(const uint8_t* header, uint8_t length); uint8_t writeHeader(const uint8_t* header, uint16_t length);
uint8_t writeData(const uint8_t* data, uint8_t length); uint8_t writeData(const uint8_t* data, uint16_t length);
uint8_t writeEOT(); uint8_t writeEOT();
void process(); void process();
@ -38,7 +38,7 @@ public:
uint8_t getSpace() const; uint8_t getSpace() const;
private: private:
CSerialRB m_buffer; CRingBuffer<uint8_t> m_buffer;
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
q15_t m_modState[20U]; // blockSize + phaseLength - 1, 8 + 9 - 1 plus some spare q15_t m_modState[20U]; // blockSize + phaseLength - 1, 8 + 9 - 1 plus some spare
uint8_t m_poBuffer[600U]; uint8_t m_poBuffer[600U];

763
FM.cpp

File diff suppressed because it is too large Load Diff

80
FM.h
View File

@ -27,28 +27,33 @@
#include "FMTimeout.h" #include "FMTimeout.h"
#include "FMKeyer.h" #include "FMKeyer.h"
#include "FMTimer.h" #include "FMTimer.h"
#include "FMRB.h" #include "RingBuffer.h"
#include "FMDirectForm1.h" #include "FMDirectForm1.h"
#include "FMDownsampler.h" #include "FMDownSampler.h"
#include "FMUpSampler.h"
#include "FMNoiseSquelch.h"
enum FM_STATE { enum FM_STATE {
FS_LISTENING, FS_LISTENING,
FS_KERCHUNK, FS_KERCHUNK_RF,
FS_RELAYING, FS_RELAYING_RF,
FS_RELAYING_WAIT, FS_RELAYING_WAIT_RF,
FS_TIMEOUT, FS_TIMEOUT_RF,
FS_TIMEOUT_WAIT, FS_TIMEOUT_WAIT_RF,
FS_KERCHUNK_EXT,
FS_RELAYING_EXT,
FS_RELAYING_WAIT_EXT,
FS_TIMEOUT_EXT,
FS_TIMEOUT_WAIT_EXT,
FS_HANG FS_HANG
}; };
class CFM { class CFM {
public: public:
CFM(); CFM();
void samples(bool cos, const q15_t* samples, uint8_t length); void samples(bool cos, q15_t* samples, uint8_t length);
void process(); void process();
@ -56,13 +61,20 @@ public:
uint8_t setCallsign(const char* callsign, uint8_t speed, uint16_t frequency, uint8_t time, uint8_t holdoff, uint8_t highLevel, uint8_t lowLevel, bool callsignAtStart, bool callsignAtEnd, bool callsignAtLatch); uint8_t setCallsign(const char* callsign, uint8_t speed, uint16_t frequency, uint8_t time, uint8_t holdoff, uint8_t highLevel, uint8_t lowLevel, bool callsignAtStart, bool callsignAtEnd, bool callsignAtLatch);
uint8_t setAck(const char* rfAck, uint8_t speed, uint16_t frequency, uint8_t minTime, uint16_t delay, uint8_t level); uint8_t setAck(const char* rfAck, uint8_t speed, uint16_t frequency, uint8_t minTime, uint16_t delay, uint8_t level);
uint8_t setMisc(uint16_t timeout, uint8_t timeoutLevel, uint8_t ctcssFrequency, uint8_t ctcssHighThreshold, uint8_t ctcssLowThreshold, uint8_t ctcssLevel, uint8_t kerchunkTime, uint8_t hangTime, uint8_t accessMode, bool cosInvert, uint8_t rfAudioBoost, uint8_t maxDev, uint8_t rxLevel); uint8_t setMisc(uint16_t timeout, uint8_t timeoutLevel, uint8_t ctcssFrequency, uint8_t ctcssHighThreshold, uint8_t ctcssLowThreshold, uint8_t ctcssLevel, uint8_t kerchunkTime, uint8_t hangTime, uint8_t accessMode, bool cosInvert, bool noiseSquelch, uint8_t squelchHighThreshold, uint8_t squelchLowThreshold, uint8_t rfAudioBoost, uint8_t maxDev, uint8_t rxLevel);
uint8_t setExt(const char* ack, uint8_t audioBoost, uint8_t speed, uint16_t frequency, uint8_t level);
uint8_t getSpace() const;
uint8_t writeData(const uint8_t* data, uint8_t length);
private: private:
CFMKeyer m_callsign; CFMKeyer m_callsign;
CFMKeyer m_rfAck; CFMKeyer m_rfAck;
CFMKeyer m_extAck;
CFMCTCSSRX m_ctcssRX; CFMCTCSSRX m_ctcssRX;
CFMCTCSSTX m_ctcssTX; CFMCTCSSTX m_ctcssTX;
CFMNoiseSquelch m_squelch;
CFMTimeout m_timeoutTone; CFMTimeout m_timeoutTone;
FM_STATE m_state; FM_STATE m_state;
bool m_callsignAtStart; bool m_callsignAtStart;
@ -75,27 +87,51 @@ private:
CFMTimer m_ackMinTimer; CFMTimer m_ackMinTimer;
CFMTimer m_ackDelayTimer; CFMTimer m_ackDelayTimer;
CFMTimer m_hangTimer; CFMTimer m_hangTimer;
CFMTimer m_statusTimer;
CFMTimer m_reverseTimer; CFMTimer m_reverseTimer;
bool m_needReverse;
CFMDirectFormI m_filterStage1; CFMDirectFormI m_filterStage1;
CFMDirectFormI m_filterStage2; CFMDirectFormI m_filterStage2;
CFMDirectFormI m_filterStage3; CFMDirectFormI m_filterStage3;
CFMBlanking m_blanking; CFMBlanking m_blanking;
uint8_t m_accessMode; uint8_t m_accessMode;
bool m_cosInvert; bool m_cosInvert;
bool m_noiseSquelch;
q15_t m_rfAudioBoost; q15_t m_rfAudioBoost;
CFMDownsampler m_downsampler; q15_t m_extAudioBoost;
CFMDownSampler m_downSampler;
bool m_extEnabled;
q15_t m_rxLevel; q15_t m_rxLevel;
CFMRB m_inputRB; CRingBuffer<q15_t> m_inputRFRB;
CFMRB m_outputRB; CRingBuffer<q15_t> m_outputRFRB;
CFMUpSampler m_inputExtRB;
void stateMachine(bool validSignal); void stateMachine(bool validRFSignal, bool validExtSignal);
void listeningState(bool validSignal);
void kerchunkState(bool validSignal); void duplexStateMachine(bool validRFSignal, bool validExtSignal);
void relayingState(bool validSignal); void listeningStateDuplex(bool validRFSignal, bool validExtSignal);
void relayingWaitState(bool validSignal); void kerchunkRFStateDuplex(bool validSignal);
void timeoutState(bool validSignal); void relayingRFStateDuplex(bool validSignal);
void timeoutWaitState(bool validSignal); void relayingRFWaitStateDuplex(bool validSignal);
void hangState(bool validSignal); void timeoutRFStateDuplex(bool validSignal);
void timeoutRFWaitStateDuplex(bool validSignal);
void kerchunkExtStateDuplex(bool validSignal);
void relayingExtStateDuplex(bool validSignal);
void relayingExtWaitStateDuplex(bool validSignal);
void timeoutExtStateDuplex(bool validSignal);
void timeoutExtWaitStateDuplex(bool validSignal);
void hangStateDuplex(bool validRFSignal, bool validExtSignal);
void simplexStateMachine(bool validRFSignal, bool validExtSignal);
void listeningStateSimplex(bool validRFSignal, bool validExtSignal);
void relayingRFStateSimplex(bool validSignal);
void relayingRFWaitStateSimplex(bool validSignal);
void timeoutRFStateSimplex(bool validSignal);
void timeoutRFWaitStateSimplex(bool validSignal);
void relayingExtStateSimplex(bool validSignal);
void relayingExtWaitStateSimplex(bool validSignal);
void timeoutExtStateSimplex(bool validSignal);
void timeoutExtWaitStateSimplex(bool validSignal);
void clock(uint8_t length); void clock(uint8_t length);

View File

@ -87,7 +87,7 @@ m_lowThreshold(0),
m_count(0U), m_count(0U),
m_q0(0), m_q0(0),
m_q1(0), m_q1(0),
m_result(CTS_NONE) m_state(false)
{ {
} }
@ -111,13 +111,11 @@ uint8_t CFMCTCSSRX::setParams(uint8_t frequency, uint8_t highThreshold, uint8_t
return 0U; return 0U;
} }
uint8_t CFMCTCSSRX::process(q15_t sample) bool CFMCTCSSRX::process(q15_t sample)
{ {
//get more dynamic into the decoder by multiplying the sample by 1.5 //get more dynamic into the decoder by multiplying the sample by 1.5
q31_t sample31 = q31_t(sample) + (q31_t(sample) >> 1); q31_t sample31 = q31_t(sample) + (q31_t(sample) >> 1);
m_result &= ~CTS_READY;
q31_t q2 = m_q1; q31_t q2 = m_q1;
m_q1 = m_q0; m_q1 = m_q0;
@ -149,33 +147,29 @@ uint8_t CFMCTCSSRX::process(q15_t sample)
// value = m_q0 * m_q0 + m_q1 * m_q1 - m_q0 * m_q1 * m_coeffDivTwo * 2 // value = m_q0 * m_q0 + m_q1 * m_q1 - m_q0 * m_q1 * m_coeffDivTwo * 2
q31_t value = t2 + t4 - t9; q31_t value = t2 + t4 - t9;
bool previousCTCSSValid = CTCSS_VALID(m_result); bool previousState = m_state;
q31_t threshold = m_highThreshold; q31_t threshold = m_highThreshold;
if (previousCTCSSValid) if (previousState)
threshold = m_lowThreshold; threshold = m_lowThreshold;
m_result |= CTS_READY; m_state = value >= threshold;
if (value >= threshold)
m_result |= CTS_VALID;
else
m_result &= ~CTS_VALID;
if (previousCTCSSValid != CTCSS_VALID(m_result)) if (previousState != m_state)
DEBUG4("CTCSS Value / Threshold / Valid", value, threshold, CTCSS_VALID(m_result)); DEBUG4("CTCSS Value / Threshold / Valid", value, threshold, m_state);
m_count = 0U; m_count = 0U;
m_q0 = 0; m_q0 = 0;
m_q1 = 0; m_q1 = 0;
} }
return m_result; return m_state;
} }
void CFMCTCSSRX::reset() void CFMCTCSSRX::reset()
{ {
m_q0 = 0; m_q0 = 0;
m_q1 = 0; m_q1 = 0;
m_result = CTS_NONE; m_state = false;
m_count = 0U; m_count = 0U;
} }

View File

@ -21,22 +21,13 @@
#include "Config.h" #include "Config.h"
const uint8_t CTS_NONE = 0U;
const uint8_t CTS_READY = 1U;
const uint8_t CTS_VALID = 2U;
#define CTCSS_READY(a) ((a & CTS_READY) != 0)
#define CTCSS_NOT_READY(a) ((a & CTS_READY) == 0)
#define CTCSS_VALID(a) ((a & CTS_VALID) != 0)
#define CTCSS_NOT_VALID(a) ((a & CTS_VALID) == 0)
class CFMCTCSSRX { class CFMCTCSSRX {
public: public:
CFMCTCSSRX(); CFMCTCSSRX();
uint8_t setParams(uint8_t frequency, uint8_t highThreshold, uint8_t lowThreshold); uint8_t setParams(uint8_t frequency, uint8_t highThreshold, uint8_t lowThreshold);
uint8_t process(q15_t sample); bool process(q15_t sample);
void reset(); void reset();
@ -47,7 +38,7 @@ private:
uint16_t m_count; uint16_t m_count;
q31_t m_q0; q31_t m_q0;
q31_t m_q1; q31_t m_q1;
uint8_t m_result; bool m_state;
}; };
#endif #endif

View File

@ -29,7 +29,7 @@ THE SOFTWARE.
// based on https://raw.githubusercontent.com/berndporr/iir_fixed_point/master/DirectFormI.h // based on https://raw.githubusercontent.com/berndporr/iir_fixed_point/master/DirectFormI.h
#include "Globals.h" #include <cstdint>
#ifndef DIRECTFORMI_H_ #ifndef DIRECTFORMI_H_
#define DIRECTFORMI_H_ #define DIRECTFORMI_H_

74
FMDownSampler.cpp Normal file
View File

@ -0,0 +1,74 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "FMDownSampler.h"
CFMDownSampler::CFMDownSampler(uint16_t length) :
m_ringBuffer(length),
m_samplePack(0U),
m_samplePackPointer(NULL),
m_sampleIndex(0U)
{
m_samplePackPointer = (uint8_t*)&m_samplePack;
}
void CFMDownSampler::addSample(q15_t sample)
{
uint32_t usample = uint32_t(int32_t(sample) + 2048);
//only take one of three samples
switch(m_sampleIndex){
case 0:
m_samplePack = usample << 12;
break;
case 3:{
m_samplePack |= usample;
//we did not use MSB; skip it
TSamplePairPack pair{m_samplePackPointer[0U], m_samplePackPointer[1U], m_samplePackPointer[2U]};
m_ringBuffer.put(pair);
m_samplePack = 0U;//reset the sample pack
}
break;
default:
//Just skip this sample
break;
}
m_sampleIndex++;
if (m_sampleIndex >= 6U)//did we pack two samples ?
m_sampleIndex = 0U;
}
bool CFMDownSampler::getPackedData(TSamplePairPack& data)
{
return m_ringBuffer.get(data);
}
uint16_t CFMDownSampler::getData()
{
return m_ringBuffer.getData();
}
void CFMDownSampler::reset()
{
m_sampleIndex = 0U;
}

View File

@ -21,23 +21,27 @@
#define FMDOWNSAMPLER_H #define FMDOWNSAMPLER_H
#include "Config.h" #include "Config.h"
#include "FMDownsampleRB.h" #include "RingBuffer.h"
#include "FMSamplePairPack.h"
class CFMDownsampler { class CFMDownSampler {
public: public:
CFMDownsampler(uint16_t length); CFMDownSampler(uint16_t length);
void addSample(q15_t sample); void addSample(q15_t sample);
inline bool getPackedData(uint8_t& data){ return m_ringBuffer.get(data); };
inline bool hasOverflowed() { return m_ringBuffer.hasOverflowed(); }; bool getPackedData(TSamplePairPack& data);
uint16_t getData();
void reset();
private: private:
CFMDownsampleRB m_ringBuffer; CRingBuffer<TSamplePairPack> m_ringBuffer;
union { uint32_t m_samplePack;
int32_t m_samplePack; uint8_t* m_samplePackPointer;
int8_t m_samplePackBytes[4]; uint8_t m_sampleIndex;
};
uint8_t m_packIndex;
uint8_t m_downSampleIndex;
}; };
#endif #endif

View File

@ -1,63 +0,0 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "FMDownsampler.h"
CFMDownsampler::CFMDownsampler(uint16_t length) :
m_ringBuffer(length),//length might need tweaking
m_packIndex(0),
m_downSampleIndex(0)
{
m_samplePack = 0;
}
void CFMDownsampler::addSample(q15_t sample)
{
//only take one of three samples
if(m_downSampleIndex == 0) {
switch(m_packIndex){
case 0:
m_samplePack = int32_t(sample) << 12;
break;
case 1:{
m_samplePack |= int32_t(sample);
//we did not use MSB; skip it
m_ringBuffer.put(m_samplePackBytes[1]);
m_ringBuffer.put(m_samplePackBytes[2]);
m_ringBuffer.put(m_samplePackBytes[3]);
m_samplePack = 0;
}
break;
default:
//should never happen
break;
}
m_packIndex++;
if(m_packIndex >= 2)
m_packIndex = 0;
}
m_downSampleIndex++;
if(m_downSampleIndex >= 3)
m_downSampleIndex = 0;
}

127
FMNoiseSquelch.cpp Normal file
View File

@ -0,0 +1,127 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "FMNoiseSquelch.h"
// 4500Hz centre frequency
const q31_t COEFF_DIV_TWO = 821806413;
// 400Hz bandwidth
const uint16_t N = 24000U / 400U;
CFMNoiseSquelch::CFMNoiseSquelch() :
m_highThreshold(0),
m_lowThreshold(0),
m_count(0U),
m_q0(0),
m_q1(0),
m_state(false),
m_validCount(0U)
{
}
void CFMNoiseSquelch::setParams(uint8_t highThreshold, uint8_t lowThreshold)
{
m_highThreshold = q31_t(highThreshold);
m_lowThreshold = q31_t(lowThreshold);
}
bool CFMNoiseSquelch::process(q15_t sample)
{
//get more dynamic into the decoder by multiplying the sample by 64
q31_t sample31 = q31_t(sample) << 6; //+ (q31_t(sample) >> 1);
q31_t q2 = m_q1;
m_q1 = m_q0;
// Q31 multiplication, t3 = m_coeffDivTwo * 2 * m_q1
q63_t t1 = COEFF_DIV_TWO * m_q1;
q31_t t2 = __SSAT((t1 >> 31), 31);
q31_t t3 = t2 * 2;
// m_q0 = m_coeffDivTwo * m_q1 * 2 - q2 + sample
m_q0 = t3 - q2 + sample31;
m_count++;
if (m_count == N) {
// Q31 multiplication, t2 = m_q0 * m_q0
q63_t t1 = q63_t(m_q0) * q63_t(m_q0);
q31_t t2 = __SSAT((t1 >> 31), 31);
// Q31 multiplication, t4 = m_q0 * m_q0
q63_t t3 = q63_t(m_q1) * q63_t(m_q1);
q31_t t4 = __SSAT((t3 >> 31), 31);
// Q31 multiplication, t9 = m_q0 * m_q1 * m_coeffDivTwo * 2
q63_t t5 = q63_t(m_q0) * q63_t(m_q1);
q31_t t6 = __SSAT((t5 >> 31), 31);
q63_t t7 = t6 * COEFF_DIV_TWO;
q31_t t8 = __SSAT((t7 >> 31), 31);
q31_t t9 = t8 * 2;
// value = m_q0 * m_q0 + m_q1 * m_q1 - m_q0 * m_q1 * m_coeffDivTwo * 2
q31_t value = t2 + t4 - t9;
bool previousState = m_state;
q31_t threshold = m_highThreshold;
if (previousState)
threshold = m_lowThreshold;
if (!m_state) {
if (value < threshold)
m_validCount++;
else
m_validCount = 0U;
}
if (m_state) {
if (value >= threshold)
m_invalidCount++;
else
m_invalidCount = 0U;
}
m_state = m_validCount >= 10U && m_invalidCount < 10U;
if(previousState && !m_state)
m_invalidCount = 0U;
if (previousState != m_state) {
DEBUG4("Noise Squelch Value / Threshold / Valid", value, threshold, m_state);
DEBUG3("Valid Count / Invalid Count", m_validCount, m_invalidCount);
}
m_count = 0U;
m_q0 = 0;
m_q1 = 0;
}
return m_state;
}
void CFMNoiseSquelch::reset()
{
m_q0 = 0;
m_q1 = 0;
m_state = false;
m_count = 0U;
}

45
FMNoiseSquelch.h Normal file
View File

@ -0,0 +1,45 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(FMNOISESQUELCH_H)
#define FMNOISESQUELCH_H
#include "Config.h"
class CFMNoiseSquelch {
public:
CFMNoiseSquelch();
void setParams(uint8_t highThreshold, uint8_t lowThreshold);
bool process(q15_t sample);
void reset();
private:
q31_t m_highThreshold;
q31_t m_lowThreshold;
uint16_t m_count;
q31_t m_q0;
q31_t m_q1;
bool m_state;
uint8_t m_validCount;
uint8_t m_invalidCount;
};
#endif

110
FMRB.cpp
View File

@ -1,110 +0,0 @@
/*
TX fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016,2020 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#include "FMRB.h"
CFMRB::CFMRB(uint16_t length) :
m_length(length),
m_head(0U),
m_tail(0U),
m_full(false),
m_overflow(false)
{
m_samples = new q15_t[length];
}
uint16_t CFMRB::getSpace() const
{
uint16_t n = 0U;
if (m_tail == m_head)
n = m_full ? 0U : m_length;
else if (m_tail < m_head)
n = m_length - m_head + m_tail;
else
n = m_tail - m_head;
if (n > m_length)
n = 0U;
return n;
}
uint16_t CFMRB::getData() const
{
if (m_tail == m_head)
return m_full ? m_length : 0U;
else if (m_tail < m_head)
return m_head - m_tail;
else
return m_length - m_tail + m_head;
}
bool CFMRB::put(q15_t sample)
{
if (m_full) {
m_overflow = true;
return false;
}
m_samples[m_head] = sample;
m_head++;
if (m_head >= m_length)
m_head = 0U;
if (m_head == m_tail)
m_full = true;
return true;
}
bool CFMRB::get(q15_t& sample)
{
if (m_head == m_tail && !m_full)
return false;
sample = m_samples[m_tail];
m_full = false;
m_tail++;
if (m_tail >= m_length)
m_tail = 0U;
return true;
}
bool CFMRB::hasOverflowed()
{
bool overflow = m_overflow;
m_overflow = false;
return overflow;
}
void CFMRB::reset()
{
m_head = 0U;
m_tail = 0U;
m_full = false;
m_overflow = false;
}

72
FMRB.h
View File

@ -1,72 +0,0 @@
/*
Serial fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016,2020 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#if !defined(FMRB_H)
#define FMRB_H
#if defined(STM32F4XX)
#include "stm32f4xx.h"
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif
#if defined(__SAM3X8E__) || defined(STM32F105xC)
#define ARM_MATH_CM3
#elif defined(STM32F7XX)
#define ARM_MATH_CM7
#elif defined(STM32F4XX) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
#define ARM_MATH_CM4
#else
#error "Unknown processor type"
#endif
#include <arm_math.h>
class CFMRB {
public:
CFMRB(uint16_t length);
uint16_t getSpace() const;
uint16_t getData() const;
bool put(q15_t sample);
bool get(q15_t& sample);
bool hasOverflowed();
void reset();
private:
uint16_t m_length;
volatile q15_t* m_samples;
volatile uint16_t m_head;
volatile uint16_t m_tail;
volatile bool m_full;
bool m_overflow;
};
#endif

29
FMSamplePairPack.h Normal file
View File

@ -0,0 +1,29 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(TSAMPLEPACK_H)
#define TSAMPLEPACK_H
struct TSamplePairPack {
uint8_t byte0;
uint8_t byte1;
uint8_t byte2;
};
#endif

97
FMUpSampler.cpp Normal file
View File

@ -0,0 +1,97 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "FMUpSampler.h"
const uint32_t FM_UPSAMPLE_MASK = 0x00000FFFU;
CFMUpSampler::CFMUpSampler() :
m_upSampleIndex(0),
m_pack(0U),
m_packPointer(NULL),
m_samples(3600U), //300ms of 12 bit 8kHz audio
m_running(false)
{
m_packPointer = (uint8_t*)&m_pack;
}
void CFMUpSampler::reset()
{
m_upSampleIndex = 0U;
m_pack = 0U;
m_samples.reset();
m_running = false;
}
void CFMUpSampler::addData(const uint8_t* data, uint16_t length)
{
TSamplePairPack* packPointer = (TSamplePairPack*)data;
TSamplePairPack* packPointerEnd = packPointer + (length / 3U);
while(packPointer != packPointerEnd) {
m_samples.put(*packPointer);
packPointer++;
}
if(!m_running)
m_running = m_samples.getData() > 300U;//75ms of audio
}
bool CFMUpSampler::getSample(q15_t& sample)
{
if(!m_running)
return false;
switch (m_upSampleIndex)
{
case 0: {
TSamplePairPack pairPack;
if(!m_samples.get(pairPack)) {
m_running = false;
return false;
}
m_pack = 0U;
m_packPointer = (uint8_t*)&m_pack;
m_packPointer[0U] = pairPack.byte0;
m_packPointer[1U] = pairPack.byte1;
m_packPointer[2U] = pairPack.byte2;
sample = q15_t(m_pack >> 12) - 2048;
break;
}
case 3:
sample = q15_t(m_pack & FM_UPSAMPLE_MASK) - 2048;
break;
default:
sample = 0;
break;
}
m_upSampleIndex++;
if(m_upSampleIndex >= 6U)
m_upSampleIndex = 0U;
return true;
}
uint16_t CFMUpSampler::getSpace() const
{
//return available space in bytes
return m_samples.getSpace() * sizeof(TSamplePairPack);
}

48
FMUpSampler.h Normal file
View File

@ -0,0 +1,48 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(FMUPSAMPLER_H)
#define FMUPSAMPLER_H
#include "Config.h"
#include "RingBuffer.h"
#include "FMSamplePairPack.h"
class CFMUpSampler {
public:
CFMUpSampler();
void reset();
void addData(const uint8_t* data, uint16_t length);
bool getSample(q15_t& sample);
uint16_t getSpace() const;
private:
uint8_t m_upSampleIndex;
uint32_t m_pack;
uint8_t * m_packPointer;
CRingBuffer<TSamplePairPack> m_samples;
bool m_running;
};
#endif

View File

@ -28,6 +28,7 @@
#include "STM32Utils.h" #include "STM32Utils.h"
#else #else
#include <Arduino.h> #include <Arduino.h>
#undef PI //Undefine PI to get rid of annoying warning as it is also defined in arm_math.h.
#endif #endif
#if defined(__SAM3X8E__) || defined(STM32F105xC) #if defined(__SAM3X8E__) || defined(STM32F105xC)
@ -52,6 +53,7 @@ enum MMDVM_STATE {
STATE_POCSAG = 6, STATE_POCSAG = 6,
STATE_M17 = 7, STATE_M17 = 7,
STATE_FM = 10, STATE_FM = 10,
STATE_AX25 = 11,
// Dummy states start at 90 // Dummy states start at 90
STATE_NXDNCAL1K = 91, STATE_NXDNCAL1K = 91,
@ -99,6 +101,8 @@ enum MMDVM_STATE {
#include "CalPOCSAG.h" #include "CalPOCSAG.h"
#include "CalRSSI.h" #include "CalRSSI.h"
#include "CWIdTX.h" #include "CWIdTX.h"
#include "AX25RX.h"
#include "AX25TX.h"
#include "Debug.h" #include "Debug.h"
#include "IO.h" #include "IO.h"
#include "FM.h" #include "FM.h"
@ -128,6 +132,7 @@ extern bool m_nxdnEnable;
extern bool m_pocsagEnable; extern bool m_pocsagEnable;
extern bool m_m17Enable; extern bool m_m17Enable;
extern bool m_fmEnable; extern bool m_fmEnable;
extern bool m_ax25Enable;
extern bool m_duplex; extern bool m_duplex;
@ -163,6 +168,9 @@ extern CM17TX m17TX;
extern CFM fm; extern CFM fm;
extern CAX25RX ax25RX;
extern CAX25TX ax25TX;
extern CCalDStarRX calDStarRX; extern CCalDStarRX calDStarRX;
extern CCalDStarTX calDStarTX; extern CCalDStarTX calDStarTX;
extern CCalDMR calDMR; extern CCalDMR calDMR;
@ -175,3 +183,4 @@ extern CCalRSSI calRSSI;
extern CCWIdTX cwIdTX; extern CCWIdTX cwIdTX;
#endif #endif

34
IO.cpp
View File

@ -90,6 +90,7 @@ m_nxdnTXLevel(128 * 128),
m_m17TXLevel(128 * 128), m_m17TXLevel(128 * 128),
m_pocsagTXLevel(128 * 128), m_pocsagTXLevel(128 * 128),
m_fmTXLevel(128 * 128), m_fmTXLevel(128 * 128),
m_ax25TXLevel(128 * 128),
m_rxDCOffset(DC_OFFSET), m_rxDCOffset(DC_OFFSET),
m_txDCOffset(DC_OFFSET), m_txDCOffset(DC_OFFSET),
m_useCOSAsLockout(false), m_useCOSAsLockout(false),
@ -306,6 +307,7 @@ void CIO::process()
if (m_txBuffer.getData() == 0U && m_tx) { if (m_txBuffer.getData() == 0U && m_tx) {
m_tx = false; m_tx = false;
setPTTInt(m_pttInvert ? true : false); setPTTInt(m_pttInvert ? true : false);
DEBUG1("TX OFF");
} }
if (m_rxBuffer.getData() >= RX_BLOCK_SIZE) { if (m_rxBuffer.getData() >= RX_BLOCK_SIZE) {
@ -314,15 +316,16 @@ void CIO::process()
uint16_t rssi[RX_BLOCK_SIZE]; uint16_t rssi[RX_BLOCK_SIZE];
for (uint16_t i = 0U; i < RX_BLOCK_SIZE; i++) { for (uint16_t i = 0U; i < RX_BLOCK_SIZE; i++) {
uint16_t sample; TSample sample;
m_rxBuffer.get(sample, control[i]); m_rxBuffer.get(sample);
control[i] = sample.control;
m_rssiBuffer.get(rssi[i]); m_rssiBuffer.get(rssi[i]);
// Detect ADC overflow // Detect ADC overflow
if (m_detect && (sample == 0U || sample == 4095U)) if (m_detect && (sample.sample == 0U || sample.sample == 4095U))
m_adcOverflow++; m_adcOverflow++;
q15_t res1 = q15_t(sample) - m_rxDCOffset; q15_t res1 = q15_t(sample.sample) - m_rxDCOffset;
q31_t res2 = res1 * m_rxLevel; q31_t res2 = res1 * m_rxLevel;
samples[i] = q15_t(__SSAT((res2 >> 15), 16)); samples[i] = q15_t(__SSAT((res2 >> 15), 16));
} }
@ -419,6 +422,14 @@ void CIO::process()
fm.samples(cos, dcSamples, RX_BLOCK_SIZE); fm.samples(cos, dcSamples, RX_BLOCK_SIZE);
#else #else
fm.samples(cos, samples, RX_BLOCK_SIZE); fm.samples(cos, samples, RX_BLOCK_SIZE);
#endif
}
if (m_ax25Enable) {
#if defined(USE_DCBLOCKER)
ax25RX.samples(dcSamples, RX_BLOCK_SIZE);
#else
ax25RX.samples(samples, RX_BLOCK_SIZE);
#endif #endif
} }
} else if (m_modemState == STATE_DSTAR) { } else if (m_modemState == STATE_DSTAR) {
@ -493,8 +504,12 @@ void CIO::process()
bool cos = getCOSInt(); bool cos = getCOSInt();
#if defined(USE_DCBLOCKER) #if defined(USE_DCBLOCKER)
fm.samples(cos, dcSamples, RX_BLOCK_SIZE); fm.samples(cos, dcSamples, RX_BLOCK_SIZE);
if (m_ax25Enable)
ax25RX.samples(dcSamples, RX_BLOCK_SIZE);
#else #else
fm.samples(cos, samples, RX_BLOCK_SIZE); fm.samples(cos, samples, RX_BLOCK_SIZE);
if (m_ax25Enable)
ax25RX.samples(samples, RX_BLOCK_SIZE);
#endif #endif
} else if (m_modemState == STATE_DSTARCAL) { } else if (m_modemState == STATE_DSTARCAL) {
q15_t GMSKVals[RX_BLOCK_SIZE]; q15_t GMSKVals[RX_BLOCK_SIZE];
@ -519,6 +534,7 @@ void CIO::write(MMDVM_STATE mode, q15_t* samples, uint16_t length, const uint8_t
if (!m_tx) { if (!m_tx) {
m_tx = true; m_tx = true;
setPTTInt(m_pttInvert ? false : true); setPTTInt(m_pttInvert ? false : true);
DEBUG1("TX ON");
} }
q15_t txLevel = 0; q15_t txLevel = 0;
@ -547,6 +563,9 @@ void CIO::write(MMDVM_STATE mode, q15_t* samples, uint16_t length, const uint8_t
case STATE_FM: case STATE_FM:
txLevel = m_fmTXLevel; txLevel = m_fmTXLevel;
break; break;
case STATE_AX25:
txLevel = m_ax25TXLevel;
break;
default: default:
txLevel = m_cwIdTXLevel; txLevel = m_cwIdTXLevel;
break; break;
@ -562,9 +581,9 @@ void CIO::write(MMDVM_STATE mode, q15_t* samples, uint16_t length, const uint8_t
m_dacOverflow++; m_dacOverflow++;
if (control == NULL) if (control == NULL)
m_txBuffer.put(res3, MARK_NONE); m_txBuffer.put({res3, MARK_NONE});
else else
m_txBuffer.put(res3, control[i]); m_txBuffer.put({res3, control[i]});
} }
} }
@ -618,7 +637,7 @@ void CIO::setMode(MMDVM_STATE state)
m_modemState = state; m_modemState = state;
} }
void CIO::setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t cwIdTXLevel, uint8_t dstarTXLevel, uint8_t dmrTXLevel, uint8_t ysfTXLevel, uint8_t p25TXLevel, uint8_t nxdnTXLevel, uint8_t m17TXLevel, uint8_t pocsagTXLevel, uint8_t fmTXLevel, int16_t txDCOffset, int16_t rxDCOffset, bool useCOSAsLockout) void CIO::setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t cwIdTXLevel, uint8_t dstarTXLevel, uint8_t dmrTXLevel, uint8_t ysfTXLevel, uint8_t p25TXLevel, uint8_t nxdnTXLevel, uint8_t m17TXLevel, uint8_t pocsagTXLevel, uint8_t fmTXLevel, uint8_t ax25TXLevel, int16_t txDCOffset, int16_t rxDCOffset, bool useCOSAsLockout)
{ {
m_pttInvert = pttInvert; m_pttInvert = pttInvert;
@ -632,6 +651,7 @@ void CIO::setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rx
m_m17TXLevel = q15_t(m17TXLevel * 128); m_m17TXLevel = q15_t(m17TXLevel * 128);
m_pocsagTXLevel = q15_t(pocsagTXLevel * 128); m_pocsagTXLevel = q15_t(pocsagTXLevel * 128);
m_fmTXLevel = q15_t(fmTXLevel * 128); m_fmTXLevel = q15_t(fmTXLevel * 128);
m_ax25TXLevel = q15_t(ax25TXLevel * 128);
m_rxDCOffset = DC_OFFSET + rxDCOffset; m_rxDCOffset = DC_OFFSET + rxDCOffset;
m_txDCOffset = DC_OFFSET + txDCOffset; m_txDCOffset = DC_OFFSET + txDCOffset;

17
IO.h
View File

@ -21,8 +21,12 @@
#include "Globals.h" #include "Globals.h"
#include "SampleRB.h" #include "RingBuffer.h"
#include "RSSIRB.h"
struct TSample {
volatile uint16_t sample;
volatile uint8_t control;
};
class CIO { class CIO {
public: public:
@ -42,7 +46,7 @@ public:
void interrupt(); void interrupt();
void setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t cwIdTXLevel, uint8_t dstarTXLevel, uint8_t dmrTXLevel, uint8_t ysfTXLevel, uint8_t p25TXLevel, uint8_t nxdnTXLevel, uint8_t m17TXLevel, uint8_t pocsagTXLevel, uint8_t fmTXLevel, int16_t txDCOffset, int16_t rxDCOffset, bool useCOSAsLockout); void setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t cwIdTXLevel, uint8_t dstarTXLevel, uint8_t dmrTXLevel, uint8_t ysfTXLevel, uint8_t p25TXLevel, uint8_t nxdnTXLevel, uint8_t m17TXLevel, uint8_t pocsagTXLevel, uint8_t fmTXLevel, uint8_t ax25TXLevel, int16_t txDCOffset, int16_t rxDCOffset, bool useCOSAsLockout);
void getOverflow(bool& adcOverflow, bool& dacOverflow); void getOverflow(bool& adcOverflow, bool& dacOverflow);
@ -59,9 +63,9 @@ public:
private: private:
bool m_started; bool m_started;
CSampleRB m_rxBuffer; CRingBuffer<TSample> m_rxBuffer;
CSampleRB m_txBuffer; CRingBuffer<TSample> m_txBuffer;
CRSSIRB m_rssiBuffer; CRingBuffer<uint16_t> m_rssiBuffer;
arm_biquad_casd_df1_inst_q31 m_dcFilter; arm_biquad_casd_df1_inst_q31 m_dcFilter;
q31_t m_dcState[4]; q31_t m_dcState[4];
@ -90,6 +94,7 @@ private:
q15_t m_m17TXLevel; q15_t m_m17TXLevel;
q15_t m_pocsagTXLevel; q15_t m_pocsagTXLevel;
q15_t m_fmTXLevel; q15_t m_fmTXLevel;
q15_t m_ax25TXLevel;
uint16_t m_rxDCOffset; uint16_t m_rxDCOffset;
uint16_t m_txDCOffset; uint16_t m_txDCOffset;

View File

@ -188,14 +188,13 @@ void CIO::startInt()
void CIO::interrupt() void CIO::interrupt()
{ {
if ((ADC->ADC_ISR & ADC_ISR_EOC_Chan) == ADC_ISR_EOC_Chan) { // Ensure there was an End-of-Conversion and we read the ISR reg if ((ADC->ADC_ISR & ADC_ISR_EOC_Chan) == ADC_ISR_EOC_Chan) { // Ensure there was an End-of-Conversion and we read the ISR reg
uint8_t control = MARK_NONE; TSample sample = {DC_OFFSET, MARK_NONE};
uint16_t sample = DC_OFFSET;
m_txBuffer.get(sample, control); m_txBuffer.get(sample);
DACC->DACC_CDR = sample; DACC->DACC_CDR = sample.sample;
sample = ADC->ADC_CDR[ADC_CDR_Chan]; sample.sample = ADC->ADC_CDR[ADC_CDR_Chan];
m_rxBuffer.put(sample, control); m_rxBuffer.put(sample);
#if defined(SEND_RSSI_DATA) #if defined(SEND_RSSI_DATA)
m_rssiBuffer.put(ADC->ADC_CDR[RSSI_CDR_Chan]); m_rssiBuffer.put(ADC->ADC_CDR[RSSI_CDR_Chan]);

View File

@ -342,25 +342,24 @@ void CIO::startInt()
void CIO::interrupt() void CIO::interrupt()
{ {
uint8_t control = MARK_NONE; TSample sample = {DC_OFFSET, MARK_NONE};
uint16_t sample = DC_OFFSET;
uint16_t rawRSSI = 0U; uint16_t rawRSSI = 0U;
m_txBuffer.get(sample, control); m_txBuffer.get(sample);
// Send the value to the DAC // Send the value to the DAC
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER) #if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
DAC_SetChannel2Data(DAC_Align_12b_R, sample); DAC_SetChannel2Data(DAC_Align_12b_R, sample.sample);
#else #else
DAC_SetChannel1Data(DAC_Align_12b_R, sample); DAC_SetChannel1Data(DAC_Align_12b_R, sample.sample);
#endif #endif
// Read value from ADC1 and ADC2 // Read value from ADC1 and ADC2
if ((ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC) == RESET)) { if ((ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC) == RESET)) {
// shouldn't be still in reset at this point so null the sample value? // shouldn't be still in reset at this point so null the sample value?
sample = 0U; sample.sample = 0U;
} else { } else {
sample = ADC_GetConversionValue(ADC1); sample.sample = ADC_GetConversionValue(ADC1);
#if defined(SEND_RSSI_DATA) #if defined(SEND_RSSI_DATA)
rawRSSI = ADC_GetConversionValue(ADC2); rawRSSI = ADC_GetConversionValue(ADC2);
#endif #endif
@ -370,7 +369,7 @@ void CIO::interrupt()
ADC_ClearFlag(ADC1, ADC_FLAG_EOC); ADC_ClearFlag(ADC1, ADC_FLAG_EOC);
ADC_SoftwareStartConv(ADC1); ADC_SoftwareStartConv(ADC1);
m_rxBuffer.put(sample, control); m_rxBuffer.put(sample);
m_rssiBuffer.put(rawRSSI); m_rssiBuffer.put(rawRSSI);
m_watchdog++; m_watchdog++;

View File

@ -370,8 +370,7 @@ void CIO::startInt()
void CIO::interrupt() void CIO::interrupt()
{ {
uint8_t control = MARK_NONE; TSample sample = {DC_OFFSET, MARK_NONE};
uint16_t sample = DC_OFFSET;
#if defined(SEND_RSSI_DATA) #if defined(SEND_RSSI_DATA)
uint16_t rawRSSI = 0U; uint16_t rawRSSI = 0U;
#endif #endif
@ -388,12 +387,12 @@ void CIO::interrupt()
*rssi_adon = 1; *rssi_adon = 1;
#endif #endif
m_txBuffer.get(sample, control); m_txBuffer.get(sample);
DAC->DHR12R1 = sample; // Send the value to the DAC DAC->DHR12R1 = sample.sample; // Send the value to the DAC
// Read value from ADC1 and ADC2 // Read value from ADC1 and ADC2
sample = ADC1->DR; // read conversion result; EOC is cleared by this read sample.sample = ADC1->DR; // read conversion result; EOC is cleared by this read
m_rxBuffer.put(sample, control); m_rxBuffer.put(sample);
#if defined(SEND_RSSI_DATA) #if defined(SEND_RSSI_DATA)
rawRSSI = ADC2->DR; rawRSSI = ADC2->DR;
m_rssiBuffer.put(rawRSSI); m_rssiBuffer.put(rawRSSI);

View File

@ -164,15 +164,14 @@ void CIO::startInt()
void CIO::interrupt() void CIO::interrupt()
{ {
uint8_t control = MARK_NONE; TSample sample = {DC_OFFSET, MARK_NONE};
uint16_t sample = DC_OFFSET;
m_txBuffer.get(sample, control); m_txBuffer.get(sample);
*(int16_t *)&(DAC0_DAT0L) = sample; *(int16_t *)&(DAC0_DAT0L) = sample.sample;
if ((ADC0_SC1A & ADC_SC1_COCO) == ADC_SC1_COCO) { if ((ADC0_SC1A & ADC_SC1_COCO) == ADC_SC1_COCO) {
sample = ADC0_RA; sample.sample = ADC0_RA;
m_rxBuffer.put(sample, control); m_rxBuffer.put(sample);
} }
#if defined(SEND_RSSI_DATA) #if defined(SEND_RSSI_DATA)

View File

@ -67,7 +67,8 @@ void CM17TX::process()
m_poBuffer[m_poLen++] = M17_START_SYNC; m_poBuffer[m_poLen++] = M17_START_SYNC;
} else { } else {
for (uint8_t i = 0U; i < M17_FRAME_LENGTH_BYTES; i++) { for (uint8_t i = 0U; i < M17_FRAME_LENGTH_BYTES; i++) {
uint8_t c = m_buffer.get(); uint8_t c = 0U;
m_buffer.get(c);
m_poBuffer[m_poLen++] = c; m_poBuffer[m_poLen++] = c;
} }
} }

View File

@ -21,7 +21,7 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CM17TX { class CM17TX {
public: public:
@ -38,7 +38,7 @@ public:
void setParams(uint8_t txHang); void setParams(uint8_t txHang);
private: private:
CSerialRB m_buffer; CRingBuffer<uint8_t> m_buffer;
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare
uint8_t m_poBuffer[1200U]; uint8_t m_poBuffer[1200U];

View File

@ -34,6 +34,7 @@ bool m_nxdnEnable = true;
bool m_m17Enable = true; bool m_m17Enable = true;
bool m_pocsagEnable = true; bool m_pocsagEnable = true;
bool m_fmEnable = true; bool m_fmEnable = true;
bool m_ax25Enable = true;
bool m_duplex = true; bool m_duplex = true;
@ -65,6 +66,8 @@ CM17TX m17TX;
CPOCSAGTX pocsagTX; CPOCSAGTX pocsagTX;
CFM fm; CFM fm;
CAX25RX ax25RX;
CAX25TX ax25TX;
CCalDStarRX calDStarRX; CCalDStarRX calDStarRX;
CCalDStarTX calDStarTX; CCalDStarTX calDStarTX;
@ -117,6 +120,9 @@ void loop()
if (m_pocsagEnable && (m_modemState == STATE_POCSAG || pocsagTX.busy())) if (m_pocsagEnable && (m_modemState == STATE_POCSAG || pocsagTX.busy()))
pocsagTX.process(); pocsagTX.process();
if (m_ax25Enable && (m_modemState == STATE_IDLE || m_modemState == STATE_FM))
ax25TX.process();
if (m_fmEnable && m_modemState == STATE_FM) if (m_fmEnable && m_modemState == STATE_FM)
fm.process(); fm.process();

View File

@ -31,6 +31,7 @@ bool m_nxdnEnable = true;
bool m_m17Enable = true; bool m_m17Enable = true;
bool m_pocsagEnable = true; bool m_pocsagEnable = true;
bool m_fmEnable = true; bool m_fmEnable = true;
bool m_ax25Enable = true;
bool m_duplex = true; bool m_duplex = true;
@ -62,6 +63,8 @@ CM17TX m17TX;
CPOCSAGTX pocsagTX; CPOCSAGTX pocsagTX;
CFM fm; CFM fm;
CAX25RX ax25RX;
CAX25TX ax25TX;
CCalDStarRX calDStarRX; CCalDStarRX calDStarRX;
CCalDStarTX calDStarTX; CCalDStarTX calDStarTX;
@ -114,6 +117,9 @@ void loop()
if (m_pocsagEnable && (m_modemState == STATE_POCSAG || pocsagTX.busy())) if (m_pocsagEnable && (m_modemState == STATE_POCSAG || pocsagTX.busy()))
pocsagTX.process(); pocsagTX.process();
if (m_ax25Enable && (m_modemState == STATE_IDLE || m_modemState == STATE_FM))
ax25TX.process();
if (m_fmEnable && m_modemState == STATE_FM) if (m_fmEnable && m_modemState == STATE_FM)
fm.process(); fm.process();

View File

@ -1,5 +1,5 @@
#!/usr/bin/make #!/usr/bin/make
# makefile for the arduino due (works with arduino IDE 1.6.11) # makefile for the arduino due (works with arduino IDE 1.6.12)
# #
# The original file can be found at https://github.com/pauldreik/arduino-due-makefile # The original file can be found at https://github.com/pauldreik/arduino-due-makefile
# #
@ -34,7 +34,7 @@ OBJCOPY:=$(ADIR)/packages/arduino/tools/arm-none-eabi-gcc/4.8.3-2014q1/bin/arm-n
C:=$(CC) C:=$(CC)
#SAM:=arduino/sam/ #SAM:=arduino/sam/
SAM:=$(ADIR)/packages/arduino/hardware/sam/1.6.11 SAM:=$(ADIR)/packages/arduino/hardware/sam/1.6.12
#CMSIS:=arduino/sam/system/CMSIS/ #CMSIS:=arduino/sam/system/CMSIS/
#LIBSAM:=arduino/sam/system/libsam #LIBSAM:=arduino/sam/system/libsam
TMPDIR:=$(PWD)/build TMPDIR:=$(PWD)/build

View File

@ -81,7 +81,8 @@ void CNXDNTX::process()
m_poBuffer[m_poLen++] = NXDN_PREAMBLE[2U]; m_poBuffer[m_poLen++] = NXDN_PREAMBLE[2U];
} else { } else {
for (uint8_t i = 0U; i < NXDN_FRAME_LENGTH_BYTES; i++) { for (uint8_t i = 0U; i < NXDN_FRAME_LENGTH_BYTES; i++) {
uint8_t c = m_buffer.get(); uint8_t c = 0U;
m_buffer.get(c);
m_poBuffer[m_poLen++] = c; m_poBuffer[m_poLen++] = c;
} }
} }
@ -122,7 +123,7 @@ void CNXDNTX::process()
} }
} }
uint8_t CNXDNTX::writeData(const uint8_t* data, uint8_t length) uint8_t CNXDNTX::writeData(const uint8_t* data, uint16_t length)
{ {
if (length != (NXDN_FRAME_LENGTH_BYTES + 1U)) if (length != (NXDN_FRAME_LENGTH_BYTES + 1U))
return 4U; return 4U;

View File

@ -21,13 +21,13 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CNXDNTX { class CNXDNTX {
public: public:
CNXDNTX(); CNXDNTX();
uint8_t writeData(const uint8_t* data, uint8_t length); uint8_t writeData(const uint8_t* data, uint16_t length);
void process(); void process();
@ -38,7 +38,7 @@ public:
void setParams(uint8_t txHang); void setParams(uint8_t txHang);
private: private:
CSerialRB m_buffer; CRingBuffer<uint8_t> m_buffer;
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
arm_fir_instance_q15 m_sincFilter; arm_fir_instance_q15 m_sincFilter;
q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare

View File

@ -75,9 +75,11 @@ void CP25TX::process()
for (uint16_t i = 0U; i < m_txDelay; i++) for (uint16_t i = 0U; i < m_txDelay; i++)
m_poBuffer[m_poLen++] = P25_START_SYNC; m_poBuffer[m_poLen++] = P25_START_SYNC;
} else { } else {
uint8_t length = m_buffer.get(); uint8_t length;
m_buffer.get(length);
for (uint8_t i = 0U; i < length; i++) { for (uint8_t i = 0U; i < length; i++) {
uint8_t c = m_buffer.get(); uint8_t c = 0U;
m_buffer.get(c);
m_poBuffer[m_poLen++] = c; m_poBuffer[m_poLen++] = c;
} }
} }
@ -118,7 +120,7 @@ void CP25TX::process()
} }
} }
uint8_t CP25TX::writeData(const uint8_t* data, uint8_t length) uint8_t CP25TX::writeData(const uint8_t* data, uint16_t length)
{ {
if (length < (P25_TERM_FRAME_LENGTH_BYTES + 1U)) if (length < (P25_TERM_FRAME_LENGTH_BYTES + 1U))
return 4U; return 4U;

View File

@ -21,13 +21,13 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CP25TX { class CP25TX {
public: public:
CP25TX(); CP25TX();
uint8_t writeData(const uint8_t* data, uint8_t length); uint8_t writeData(const uint8_t* data, uint16_t length);
void process(); void process();
@ -38,7 +38,7 @@ public:
void setParams(uint8_t txHang); void setParams(uint8_t txHang);
private: private:
CSerialRB m_buffer; CRingBuffer<uint8_t> m_buffer;
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
arm_fir_instance_q15 m_lpFilter; arm_fir_instance_q15 m_lpFilter;
q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2018 by Jonathan Naylor G4KLX * Copyright (C) 2009-2018,2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -61,7 +61,8 @@ void CPOCSAGTX::process()
m_poBuffer[m_poLen++] = POCSAG_SYNC; m_poBuffer[m_poLen++] = POCSAG_SYNC;
} else { } else {
for (uint8_t i = 0U; i < POCSAG_FRAME_LENGTH_BYTES; i++) { for (uint8_t i = 0U; i < POCSAG_FRAME_LENGTH_BYTES; i++) {
uint8_t c = m_buffer.get(); uint8_t c = 0U;
m_buffer.get(c);
m_poBuffer[m_poLen++] = c; m_poBuffer[m_poLen++] = c;
} }
} }
@ -95,7 +96,7 @@ bool CPOCSAGTX::busy()
return false; return false;
} }
uint8_t CPOCSAGTX::writeData(const uint8_t* data, uint8_t length) uint8_t CPOCSAGTX::writeData(const uint8_t* data, uint16_t length)
{ {
if (length != POCSAG_FRAME_LENGTH_BYTES) if (length != POCSAG_FRAME_LENGTH_BYTES)
return 4U; return 4U;
@ -146,4 +147,3 @@ uint8_t CPOCSAGTX::getSpace() const
{ {
return m_buffer.getSpace() / POCSAG_FRAME_LENGTH_BYTES; return m_buffer.getSpace() / POCSAG_FRAME_LENGTH_BYTES;
} }

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2015-2019 by Jonathan Naylor G4KLX * Copyright (C) 2015-2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -21,13 +21,13 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CPOCSAGTX { class CPOCSAGTX {
public: public:
CPOCSAGTX(); CPOCSAGTX();
uint8_t writeData(const uint8_t* data, uint8_t length); uint8_t writeData(const uint8_t* data, uint16_t length);
void writeByte(uint8_t c); void writeByte(uint8_t c);
@ -40,7 +40,7 @@ public:
bool busy(); bool busy();
private: private:
CSerialRB m_buffer; CRingBuffer<uint8_t> m_buffer;
arm_fir_instance_q15 m_modFilter; arm_fir_instance_q15 m_modFilter;
q15_t m_modState[170U]; // NoTaps + BlockSize - 1, 6 + 160 - 1 plus some spare q15_t m_modState[170U]; // NoTaps + BlockSize - 1, 6 + 160 - 1 plus some spare
uint8_t m_poBuffer[200U]; uint8_t m_poBuffer[200U];

View File

@ -1,102 +0,0 @@
/*
TX fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#include "RSSIRB.h"
CRSSIRB::CRSSIRB(uint16_t length) :
m_length(length),
m_head(0U),
m_tail(0U),
m_full(false),
m_overflow(false)
{
m_rssi = new uint16_t[length];
}
uint16_t CRSSIRB::getSpace() const
{
uint16_t n = 0U;
if (m_tail == m_head)
n = m_full ? 0U : m_length;
else if (m_tail < m_head)
n = m_length - m_head + m_tail;
else
n = m_tail - m_head;
if (n > m_length)
n = 0U;
return n;
}
uint16_t CRSSIRB::getData() const
{
if (m_tail == m_head)
return m_full ? m_length : 0U;
else if (m_tail < m_head)
return m_head - m_tail;
else
return m_length - m_tail + m_head;
}
bool CRSSIRB::put(uint16_t rssi)
{
if (m_full) {
m_overflow = true;
return false;
}
m_rssi[m_head] = rssi;
m_head++;
if (m_head >= m_length)
m_head = 0U;
if (m_head == m_tail)
m_full = true;
return true;
}
bool CRSSIRB::get(uint16_t& rssi)
{
if (m_head == m_tail && !m_full)
return false;
rssi = m_rssi[m_tail];
m_full = false;
m_tail++;
if (m_tail >= m_length)
m_tail = 0U;
return true;
}
bool CRSSIRB::hasOverflowed()
{
bool overflow = m_overflow;
m_overflow = false;
return overflow;
}

View File

@ -1,59 +0,0 @@
/*
Serial fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#if !defined(RSSIRB_H)
#define RSSIRB_H
#if defined(STM32F4XX)
#include "stm32f4xx.h"
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif
class CRSSIRB {
public:
CRSSIRB(uint16_t length);
uint16_t getSpace() const;
uint16_t getData() const;
bool put(uint16_t rssi);
bool get(uint16_t& rssi);
bool hasOverflowed();
private:
uint16_t m_length;
volatile uint16_t* m_rssi;
volatile uint16_t m_head;
volatile uint16_t m_tail;
volatile bool m_full;
bool m_overflow;
};
#endif

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2020 by Jonathan Naylor G4KLX * Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -16,8 +17,8 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/ */
#if !defined(FMDOWNSAMPLERB_H) #if !defined(RINGBUFFER_H)
#define FMDOWNSAMPLERB_H #define RINGBUFFER_H
#if defined(STM32F4XX) #if defined(STM32F4XX)
#include "stm32f4xx.h" #include "stm32f4xx.h"
@ -28,6 +29,7 @@
#include <cstddef> #include <cstddef>
#else #else
#include <Arduino.h> #include <Arduino.h>
#undef PI
#endif #endif
#if defined(__SAM3X8E__) || defined(STM32F105xC) #if defined(__SAM3X8E__) || defined(STM32F105xC)
@ -42,27 +44,34 @@
#include <arm_math.h> #include <arm_math.h>
class CFMDownsampleRB { template <typename TDATATYPE>
class CRingBuffer {
public: public:
CFMDownsampleRB(uint16_t length); CRingBuffer(uint16_t length = 370U);
uint16_t getSpace() const; uint16_t getSpace() const;
uint16_t getData() const; uint16_t getData() const;
bool put(uint8_t sample); bool put(TDATATYPE item) volatile;
bool get(uint8_t& sample); bool get(TDATATYPE& item) volatile;
TDATATYPE peek() const;
bool hasOverflowed(); bool hasOverflowed();
void reset();
private: private:
uint16_t m_length; uint16_t m_length;
volatile uint8_t* m_samples; TDATATYPE* m_buffer;
volatile uint16_t m_head; volatile uint16_t m_head;
volatile uint16_t m_tail; volatile uint16_t m_tail;
volatile bool m_full; volatile bool m_full;
bool m_overflow; bool m_overflow;
}; };
#include "RingBuffer.impl.h"
#endif #endif

View File

@ -1,5 +1,6 @@
/* /*
* Copyright (C) 2020 by Jonathan Naylor G4KLX * Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020 by Geoffrey Merck F4FXL - KC3FRA
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -16,20 +17,19 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA. * Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/ */
#include "RingBuffer.h"
#include "FMDownsampleRB.h" template <typename TDATATYPE> CRingBuffer<TDATATYPE>::CRingBuffer(uint16_t length) :
CFMDownsampleRB::CFMDownsampleRB(uint16_t length) :
m_length(length), m_length(length),
m_head(0U), m_head(0U),
m_tail(0U), m_tail(0U),
m_full(false), m_full(false),
m_overflow(false) m_overflow(false)
{ {
m_samples = new uint8_t[length]; m_buffer = new TDATATYPE[length];
} }
uint16_t CFMDownsampleRB::getSpace() const template <typename TDATATYPE> uint16_t CRingBuffer<TDATATYPE>::getSpace() const
{ {
uint16_t n = 0U; uint16_t n = 0U;
@ -46,7 +46,7 @@ uint16_t CFMDownsampleRB::getSpace() const
return n; return n;
} }
uint16_t CFMDownsampleRB::getData() const template <typename TDATATYPE> uint16_t CRingBuffer<TDATATYPE>::getData() const
{ {
if (m_tail == m_head) if (m_tail == m_head)
return m_full ? m_length : 0U; return m_full ? m_length : 0U;
@ -56,14 +56,14 @@ uint16_t CFMDownsampleRB::getData() const
return m_length - m_tail + m_head; return m_length - m_tail + m_head;
} }
bool CFMDownsampleRB::put(uint8_t sample) template <typename TDATATYPE> bool CRingBuffer<TDATATYPE>::put(TDATATYPE item) volatile
{ {
if (m_full) { if (m_full) {
m_overflow = true; m_overflow = true;
return false; return false;
} }
m_samples[m_head] = sample; m_buffer[m_head] = item;
m_head++; m_head++;
if (m_head >= m_length) if (m_head >= m_length)
@ -75,12 +75,17 @@ bool CFMDownsampleRB::put(uint8_t sample)
return true; return true;
} }
bool CFMDownsampleRB::get(uint8_t& sample) template <typename TDATATYPE> TDATATYPE CRingBuffer<TDATATYPE>::peek() const
{
return m_buffer[m_tail];
}
template <typename TDATATYPE> bool CRingBuffer<TDATATYPE>::get(TDATATYPE& item) volatile
{ {
if (m_head == m_tail && !m_full) if (m_head == m_tail && !m_full)
return false; return false;
sample = m_samples[m_tail]; item = m_buffer[m_tail];
m_full = false; m_full = false;
@ -91,7 +96,7 @@ bool CFMDownsampleRB::get(uint8_t& sample)
return true; return true;
} }
bool CFMDownsampleRB::hasOverflowed() template <typename TDATATYPE> bool CRingBuffer<TDATATYPE>::hasOverflowed()
{ {
bool overflow = m_overflow; bool overflow = m_overflow;
@ -99,3 +104,11 @@ bool CFMDownsampleRB::hasOverflowed()
return overflow; return overflow;
} }
template <typename TDATATYPE> void CRingBuffer<TDATATYPE>::reset()
{
m_head = 0U;
m_tail = 0U;
m_full = false;
m_overflow = false;
}

100
STMUART.cpp Normal file
View File

@ -0,0 +1,100 @@
/*
* Copyright (c) 2020 by Jonathan Naylor G4KLX
* Copyright (c) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if defined(STM32F4XX) || defined(STM32F7XX)
#include "STMUART.h"
CSTMUART::CSTMUART() :
m_usart(NULL)
{
}
void CSTMUART::init(USART_TypeDef* usart)
{
m_usart = usart;
}
void CSTMUART::write(const uint8_t * data, uint16_t length)
{
if(length == 0U || m_usart == NULL)
return;
m_txFifo.put(data[0]);
USART_ITConfig(m_usart, USART_IT_TXE, ENABLE);//switch TX IRQ is on
for(uint16_t i = 1U; i < length; i++) {
m_txFifo.put(data[i]);
}
USART_ITConfig(m_usart, USART_IT_TXE, ENABLE);//make sure TX IRQ is on
}
uint8_t CSTMUART::read()
{
return m_rxFifo.get();
}
void CSTMUART::handleIRQ()
{
if(m_usart == NULL)
return;
if (USART_GetITStatus(m_usart, USART_IT_RXNE)) {
if(!m_rxFifo.isFull())
m_rxFifo.put((uint8_t) USART_ReceiveData(m_usart));
USART_ClearITPendingBit(USART1, USART_IT_RXNE);
}
if (USART_GetITStatus(m_usart, USART_IT_TXE)) {
if(!m_txFifo.isEmpty())
USART_SendData(m_usart, m_txFifo.get());
USART_ClearITPendingBit(m_usart, USART_IT_TXE);
if (m_txFifo.isEmpty()) // if there's no more data to transmit then turn off TX interrupts
USART_ITConfig(m_usart, USART_IT_TXE, DISABLE);
}
}
// Flushes the transmit shift register
// warning: this call is blocking
void CSTMUART::flush()
{
if(m_usart == NULL)
return;
// wait until the TXE shows the shift register is empty
while (USART_GetITStatus(m_usart, USART_FLAG_TXE))
;
}
uint16_t CSTMUART::available()
{
return m_rxFifo.isEmpty() ? 0U : 1U;
}
uint16_t CSTMUART::availableForWrite()
{
return m_txFifo.isFull() ? 0U : 1U;
}
#endif

91
STMUART.h Normal file
View File

@ -0,0 +1,91 @@
/*
* Copyright (c) 2020 by Jonathan Naylor G4KLX
* Copyright (c) 2020 by Geoffrey Merck F4FXL - KC3FRA
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if defined(STM32F4XX) || defined(STM32F7XX)
#if !defined(STMUART_H)
#define STMUART_H
#if defined(STM32F4XX)
#include "stm32f4xx.h"
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#endif
const uint16_t BUFFER_SIZE = 2048U; //needs to be a power of 2 !
const uint16_t BUFFER_MASK = BUFFER_SIZE - 1;
class CSTMUARTFIFO {
public:
CSTMUARTFIFO() :
m_head(0U),
m_tail(0U)
{
}
void put(uint8_t data)
{
m_buffer[BUFFER_MASK & (m_head++)] = data;
}
uint8_t get()
{
return m_buffer[BUFFER_MASK & (m_tail++)];
}
void reset()
{
m_tail = 0U;
m_head = 0U;
}
bool isEmpty()
{
return m_tail == m_head;
}
bool isFull()
{
return ((m_head + 1U) & BUFFER_MASK) == (m_tail & BUFFER_MASK);
}
private:
volatile uint8_t m_buffer[BUFFER_SIZE];
volatile uint16_t m_head;
volatile uint16_t m_tail;
};
class CSTMUART {
public:
CSTMUART();
void init(USART_TypeDef* usart);
void write(const uint8_t * data, uint16_t length);
uint8_t read();
void handleIRQ();
void flush();
uint16_t available();
uint16_t availableForWrite();
private:
USART_TypeDef * m_usart;
CSTMUARTFIFO m_rxFifo;
CSTMUARTFIFO m_txFifo;
};
#endif
#endif

View File

@ -1,106 +0,0 @@
/*
TX fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#include "SampleRB.h"
CSampleRB::CSampleRB(uint16_t length) :
m_length(length),
m_head(0U),
m_tail(0U),
m_full(false),
m_overflow(false)
{
m_samples = new uint16_t[length];
m_control = new uint8_t[length];
}
uint16_t CSampleRB::getSpace() const
{
uint16_t n = 0U;
if (m_tail == m_head)
n = m_full ? 0U : m_length;
else if (m_tail < m_head)
n = m_length - m_head + m_tail;
else
n = m_tail - m_head;
if (n > m_length)
n = 0U;
return n;
}
uint16_t CSampleRB::getData() const
{
if (m_tail == m_head)
return m_full ? m_length : 0U;
else if (m_tail < m_head)
return m_head - m_tail;
else
return m_length - m_tail + m_head;
}
bool CSampleRB::put(uint16_t sample, uint8_t control)
{
if (m_full) {
m_overflow = true;
return false;
}
m_samples[m_head] = sample;
m_control[m_head] = control;
m_head++;
if (m_head >= m_length)
m_head = 0U;
if (m_head == m_tail)
m_full = true;
return true;
}
bool CSampleRB::get(uint16_t& sample, uint8_t& control)
{
if (m_head == m_tail && !m_full)
return false;
sample = m_samples[m_tail];
control = m_control[m_tail];
m_full = false;
m_tail++;
if (m_tail >= m_length)
m_tail = 0U;
return true;
}
bool CSampleRB::hasOverflowed()
{
bool overflow = m_overflow;
m_overflow = false;
return overflow;
}

View File

@ -1,60 +0,0 @@
/*
Serial fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#if !defined(SAMPLERB_H)
#define SAMPLERB_H
#if defined(STM32F4XX)
#include "stm32f4xx.h"
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif
class CSampleRB {
public:
CSampleRB(uint16_t length);
uint16_t getSpace() const;
uint16_t getData() const;
bool put(uint16_t sample, uint8_t control);
bool get(uint16_t& sample, uint8_t& control);
bool hasOverflowed();
private:
uint16_t m_length;
volatile uint16_t* m_samples;
volatile uint8_t* m_control;
volatile uint16_t m_head;
volatile uint16_t m_tail;
volatile bool m_full;
bool m_overflow;
};
#endif

View File

@ -68,9 +68,15 @@ const uint8_t MMDVM_M17_LOST = 0x46U;
const uint8_t MMDVM_POCSAG_DATA = 0x50U; const uint8_t MMDVM_POCSAG_DATA = 0x50U;
const uint8_t MMDVM_AX25_DATA = 0x55U;
const uint8_t MMDVM_FM_PARAMS1 = 0x60U; const uint8_t MMDVM_FM_PARAMS1 = 0x60U;
const uint8_t MMDVM_FM_PARAMS2 = 0x61U; const uint8_t MMDVM_FM_PARAMS2 = 0x61U;
const uint8_t MMDVM_FM_PARAMS3 = 0x62U; const uint8_t MMDVM_FM_PARAMS3 = 0x62U;
const uint8_t MMDVM_FM_PARAMS4 = 0x63U;
const uint8_t MMDVM_FM_DATA = 0x65U;
const uint8_t MMDVM_FM_STATUS = 0x66U;
const uint8_t MMDVM_FM_EOT = 0x67U;
const uint8_t MMDVM_ACK = 0x70U; const uint8_t MMDVM_ACK = 0x70U;
const uint8_t MMDVM_NAK = 0x7FU; const uint8_t MMDVM_NAK = 0x7FU;
@ -106,7 +112,7 @@ const uint8_t MMDVM_DEBUG5 = 0xF5U;
#define HW_TYPE "MMDVM" #define HW_TYPE "MMDVM"
#endif #endif
#define DESCRIPTION "20201015 (D-Star/DMR/System Fusion/P25/NXDN/M17/POCSAG/FM)" #define DESCRIPTION "20201106 (D-Star/DMR/System Fusion/P25/NXDN/M17/POCSAG/FM/AX.25)"
#if defined(GITVERSION) #if defined(GITVERSION)
#define concat(h, a, b, c) h " " a " " b " GitID #" c "" #define concat(h, a, b, c) h " " a " " b " GitID #" c ""
@ -161,82 +167,69 @@ void CSerialPort::getStatus()
// Send all sorts of interesting internal values // Send all sorts of interesting internal values
reply[0U] = MMDVM_FRAME_START; reply[0U] = MMDVM_FRAME_START;
reply[1U] = 14U; reply[1U] = 15U;
reply[2U] = MMDVM_GET_STATUS; reply[2U] = MMDVM_GET_STATUS;
reply[3U] = 0x00U; reply[3U] = uint8_t(m_modemState);
if (m_dstarEnable)
reply[3U] |= 0x01U;
if (m_dmrEnable)
reply[3U] |= 0x02U;
if (m_ysfEnable)
reply[3U] |= 0x04U;
if (m_p25Enable)
reply[3U] |= 0x08U;
if (m_nxdnEnable)
reply[3U] |= 0x10U;
if (m_pocsagEnable)
reply[3U] |= 0x20U;
if (m_fmEnable)
reply[3U] |= 0x40U;
if (m_m17Enable)
reply[3U] |= 0x80U;
reply[4U] = uint8_t(m_modemState); reply[4U] = m_tx ? 0x01U : 0x00U;
reply[5U] = m_tx ? 0x01U : 0x00U;
bool adcOverflow; bool adcOverflow;
bool dacOverflow; bool dacOverflow;
io.getOverflow(adcOverflow, dacOverflow); io.getOverflow(adcOverflow, dacOverflow);
if (adcOverflow) if (adcOverflow)
reply[5U] |= 0x02U; reply[4U] |= 0x02U;
if (io.hasRXOverflow()) if (io.hasRXOverflow())
reply[5U] |= 0x04U; reply[4U] |= 0x04U;
if (io.hasTXOverflow()) if (io.hasTXOverflow())
reply[5U] |= 0x08U; reply[4U] |= 0x08U;
if (io.hasLockout()) if (io.hasLockout())
reply[5U] |= 0x10U; reply[4U] |= 0x10U;
if (dacOverflow) if (dacOverflow)
reply[5U] |= 0x20U; reply[4U] |= 0x20U;
reply[5U] |= m_dcd ? 0x40U : 0x00U; reply[4U] |= m_dcd ? 0x40U : 0x00U;
if (m_dstarEnable) if (m_dstarEnable)
reply[6U] = dstarTX.getSpace(); reply[5U] = dstarTX.getSpace();
else else
reply[6U] = 0U; reply[5U] = 0U;
if (m_dmrEnable) { if (m_dmrEnable) {
if (m_duplex) { if (m_duplex) {
reply[7U] = dmrTX.getSpace1(); reply[6U] = dmrTX.getSpace1();
reply[8U] = dmrTX.getSpace2(); reply[7U] = dmrTX.getSpace2();
} else { } else {
reply[7U] = 10U; reply[6U] = 10U;
reply[8U] = dmrDMOTX.getSpace(); reply[7U] = dmrDMOTX.getSpace();
} }
} else { } else {
reply[6U] = 0U;
reply[7U] = 0U; reply[7U] = 0U;
reply[8U] = 0U;
} }
if (m_ysfEnable) if (m_ysfEnable)
reply[9U] = ysfTX.getSpace(); reply[8U] = ysfTX.getSpace();
else
reply[8U] = 0U;
if (m_p25Enable)
reply[9U] = p25TX.getSpace();
else else
reply[9U] = 0U; reply[9U] = 0U;
if (m_p25Enable) if (m_nxdnEnable)
reply[10U] = p25TX.getSpace(); reply[10U] = nxdnTX.getSpace();
else else
reply[10U] = 0U; reply[10U] = 0U;
if (m_nxdnEnable) if (m_m17Enable)
reply[11U] = nxdnTX.getSpace(); reply[11U] = m17TX.getSpace();
else else
reply[11U] = 0U; reply[11U] = 0U;
@ -245,12 +238,17 @@ void CSerialPort::getStatus()
else else
reply[12U] = 0U; reply[12U] = 0U;
if (m_m17Enable) if (m_fmEnable)
reply[13U] = m17TX.getSpace(); reply[13U] = fm.getSpace();
else else
reply[13U] = 0U; reply[13U] = 0U;
writeInt(1U, reply, 14); if (m_ax25Enable)
reply[14U] = ax25TX.getSpace();
else
reply[14U] = 0U;
writeInt(1U, reply, 15);
} }
void CSerialPort::getVersion() void CSerialPort::getVersion()
@ -272,9 +270,9 @@ void CSerialPort::getVersion()
writeInt(1U, reply, count); writeInt(1U, reply, count);
} }
uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length) uint8_t CSerialPort::setConfig(const uint8_t* data, uint16_t length)
{ {
if (length < 23U) if (length < 28U)
return 4U; return 4U;
bool rxInvert = (data[0U] & 0x01U) == 0x01U; bool rxInvert = (data[0U] & 0x01U) == 0x01U;
@ -291,15 +289,17 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
bool ysfEnable = (data[1U] & 0x04U) == 0x04U; bool ysfEnable = (data[1U] & 0x04U) == 0x04U;
bool p25Enable = (data[1U] & 0x08U) == 0x08U; bool p25Enable = (data[1U] & 0x08U) == 0x08U;
bool nxdnEnable = (data[1U] & 0x10U) == 0x10U; bool nxdnEnable = (data[1U] & 0x10U) == 0x10U;
bool pocsagEnable = (data[1U] & 0x20U) == 0x20U; bool fmEnable = (data[1U] & 0x20U) == 0x20U;
bool fmEnable = (data[1U] & 0x40U) == 0x40U; bool m17Enable = (data[1U] & 0x40U) == 0x40U;
bool m17Enable = (data[1U] & 0x80U) == 0x80U;
uint8_t txDelay = data[2U]; bool pocsagEnable = (data[2U] & 0x01U) == 0x01U;
bool ax25Enable = (data[2U] & 0x02U) == 0x02U;
uint8_t txDelay = data[3U];
if (txDelay > 50U) if (txDelay > 50U)
return 4U; return 4U;
MMDVM_STATE modemState = MMDVM_STATE(data[3U]); MMDVM_STATE modemState = MMDVM_STATE(data[4U]);
if (modemState != STATE_IDLE && modemState != STATE_DSTAR && modemState != STATE_DMR && modemState != STATE_YSF && modemState != STATE_P25 && modemState != STATE_NXDN && modemState != STATE_M17 && modemState != STATE_POCSAG && modemState != STATE_FM && modemState != STATE_DSTARCAL && modemState != STATE_DMRCAL && modemState != STATE_RSSICAL && modemState != STATE_LFCAL && modemState != STATE_DMRCAL1K && modemState != STATE_P25CAL1K && modemState != STATE_DMRDMO1K && modemState != STATE_NXDNCAL1K && modemState != STATE_POCSAGCAL && modemState != STATE_FMCAL10K && modemState != STATE_FMCAL12K && modemState != STATE_FMCAL15K && modemState != STATE_FMCAL20K && modemState != STATE_FMCAL25K && modemState != STATE_FMCAL30K) if (modemState != STATE_IDLE && modemState != STATE_DSTAR && modemState != STATE_DMR && modemState != STATE_YSF && modemState != STATE_P25 && modemState != STATE_NXDN && modemState != STATE_M17 && modemState != STATE_POCSAG && modemState != STATE_FM && modemState != STATE_DSTARCAL && modemState != STATE_DMRCAL && modemState != STATE_RSSICAL && modemState != STATE_LFCAL && modemState != STATE_DMRCAL1K && modemState != STATE_P25CAL1K && modemState != STATE_DMRDMO1K && modemState != STATE_NXDNCAL1K && modemState != STATE_POCSAGCAL && modemState != STATE_FMCAL10K && modemState != STATE_FMCAL12K && modemState != STATE_FMCAL15K && modemState != STATE_FMCAL20K && modemState != STATE_FMCAL25K && modemState != STATE_FMCAL30K)
return 4U; return 4U;
@ -320,37 +320,40 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
if (modemState == STATE_FM && !fmEnable) if (modemState == STATE_FM && !fmEnable)
return 4U; return 4U;
uint8_t rxLevel = data[4U]; int16_t txDCOffset = int16_t(data[5U]) - 128;
int16_t rxDCOffset = int16_t(data[6U]) - 128;
uint8_t colorCode = data[6U]; uint8_t rxLevel = data[7U];
if (colorCode > 15U)
return 4U;
uint8_t dmrDelay = data[7U]; uint8_t cwIdTXLevel = data[8U];
uint8_t cwIdTXLevel = data[5U];
uint8_t dstarTXLevel = data[9U]; uint8_t dstarTXLevel = data[9U];
uint8_t dmrTXLevel = data[10U]; uint8_t dmrTXLevel = data[10U];
uint8_t ysfTXLevel = data[11U]; uint8_t ysfTXLevel = data[11U];
uint8_t p25TXLevel = data[12U]; uint8_t p25TXLevel = data[12U];
uint8_t nxdnTXLevel = data[13U];
uint8_t m17TXLevel = data[14U];
uint8_t pocsagTXLevel = data[15U];
uint8_t fmTXLevel = data[16U];
uint8_t ax25TXLevel = data[17U];
int16_t txDCOffset = int16_t(data[13U]) - 128; uint8_t ysfTXHang = data[18U];
int16_t rxDCOffset = int16_t(data[14U]) - 128;
uint8_t nxdnTXLevel = data[15U];
uint8_t ysfTXHang = data[16U];
uint8_t pocsagTXLevel = data[17U];
uint8_t fmTXLevel = data[18U];
uint8_t p25TXHang = data[19U]; uint8_t p25TXHang = data[19U];
uint8_t nxdnTXHang = data[20U]; uint8_t nxdnTXHang = data[20U];
uint8_t m17TXHang = data[21U];
uint8_t m17TXLevel = data[21U]; uint8_t colorCode = data[22U];
uint8_t m17TXHang = data[22U]; if (colorCode > 15U)
return 4U;
uint8_t dmrDelay = data[23U];
int8_t ax25RXTwist = int8_t(data[24U]) - 128;
if (ax25RXTwist < -4 || ax25RXTwist > 10)
return 4U;
uint8_t ax25TXDelay = data[25U];
uint8_t ax25SlotTime = data[26U];
uint8_t ax25PPersist = data[27U];
setMode(modemState); setMode(modemState);
@ -362,6 +365,7 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
m_m17Enable = m17Enable; m_m17Enable = m17Enable;
m_pocsagEnable = pocsagEnable; m_pocsagEnable = pocsagEnable;
m_fmEnable = fmEnable; m_fmEnable = fmEnable;
m_ax25Enable = ax25Enable;
m_duplex = !simplex; m_duplex = !simplex;
dstarTX.setTXDelay(txDelay); dstarTX.setTXDelay(txDelay);
@ -371,6 +375,7 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
nxdnTX.setTXDelay(txDelay); nxdnTX.setTXDelay(txDelay);
m17TX.setTXDelay(txDelay); m17TX.setTXDelay(txDelay);
pocsagTX.setTXDelay(txDelay); pocsagTX.setTXDelay(txDelay);
ax25TX.setTXDelay(ax25TXDelay);
dmrTX.setColorCode(colorCode); dmrTX.setColorCode(colorCode);
dmrRX.setColorCode(colorCode); dmrRX.setColorCode(colorCode);
@ -382,15 +387,16 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
p25TX.setParams(p25TXHang); p25TX.setParams(p25TXHang);
nxdnTX.setParams(nxdnTXHang); nxdnTX.setParams(nxdnTXHang);
m17TX.setParams(m17TXHang); m17TX.setParams(m17TXHang);
ax25RX.setParams(ax25RXTwist, ax25SlotTime, ax25PPersist);
io.setParameters(rxInvert, txInvert, pttInvert, rxLevel, cwIdTXLevel, dstarTXLevel, dmrTXLevel, ysfTXLevel, p25TXLevel, nxdnTXLevel, m17TXLevel, pocsagTXLevel, fmTXLevel, txDCOffset, rxDCOffset, useCOSAsLockout); io.setParameters(rxInvert, txInvert, pttInvert, rxLevel, cwIdTXLevel, dstarTXLevel, dmrTXLevel, ysfTXLevel, p25TXLevel, nxdnTXLevel, m17TXLevel, pocsagTXLevel, fmTXLevel, ax25TXLevel, txDCOffset, rxDCOffset, useCOSAsLockout);
io.start(); io.start();
return 0U; return 0U;
} }
uint8_t CSerialPort::setFMParams1(const uint8_t* data, uint8_t length) uint8_t CSerialPort::setFMParams1(const uint8_t* data, uint16_t length)
{ {
if (length < 8U) if (length < 8U)
return 4U; return 4U;
@ -415,7 +421,7 @@ uint8_t CSerialPort::setFMParams1(const uint8_t* data, uint8_t length)
return fm.setCallsign(callsign, speed, frequency, time, holdoff, highLevel, lowLevel, callAtStart, callAtEnd, callAtLatch); return fm.setCallsign(callsign, speed, frequency, time, holdoff, highLevel, lowLevel, callAtStart, callAtEnd, callAtLatch);
} }
uint8_t CSerialPort::setFMParams2(const uint8_t* data, uint8_t length) uint8_t CSerialPort::setFMParams2(const uint8_t* data, uint16_t length)
{ {
if (length < 6U) if (length < 6U)
return 4U; return 4U;
@ -435,9 +441,9 @@ uint8_t CSerialPort::setFMParams2(const uint8_t* data, uint8_t length)
return fm.setAck(ack, speed, frequency, minTime, delay, level); return fm.setAck(ack, speed, frequency, minTime, delay, level);
} }
uint8_t CSerialPort::setFMParams3(const uint8_t* data, uint8_t length) uint8_t CSerialPort::setFMParams3(const uint8_t* data, uint16_t length)
{ {
if (length < 12U) if (length < 14U)
return 4U; return 4U;
uint16_t timeout = data[0U] * 5U; uint16_t timeout = data[0U] * 5U;
@ -451,17 +457,40 @@ uint8_t CSerialPort::setFMParams3(const uint8_t* data, uint8_t length)
uint8_t kerchunkTime = data[6U]; uint8_t kerchunkTime = data[6U];
uint8_t hangTime = data[7U]; uint8_t hangTime = data[7U];
uint8_t accessMode = data[8U] & 0x7FU; uint8_t accessMode = data[8U] & 0x0FU;
bool noiseSquelch = (data[8U] & 0x40U) == 0x40U;
bool cosInvert = (data[8U] & 0x80U) == 0x80U; bool cosInvert = (data[8U] & 0x80U) == 0x80U;
uint8_t rfAudioBoost = data[9U]; uint8_t rfAudioBoost = data[9U];
uint8_t maxDev = data[10U]; uint8_t maxDev = data[10U];
uint8_t rxLevel = data[11U]; uint8_t rxLevel = data[11U];
return fm.setMisc(timeout, timeoutLevel, ctcssFrequency, ctcssHighThreshold, ctcssLowThreshold, ctcssLevel, kerchunkTime, hangTime, accessMode, cosInvert, rfAudioBoost, maxDev, rxLevel); uint8_t squelchHighThreshold = data[12U];
uint8_t squelchLowThreshold = data[13U];
return fm.setMisc(timeout, timeoutLevel, ctcssFrequency, ctcssHighThreshold, ctcssLowThreshold, ctcssLevel, kerchunkTime, hangTime, accessMode, cosInvert, noiseSquelch, squelchHighThreshold, squelchLowThreshold, rfAudioBoost, maxDev, rxLevel);
} }
uint8_t CSerialPort::setMode(const uint8_t* data, uint8_t length) uint8_t CSerialPort::setFMParams4(const uint8_t* data, uint16_t length)
{
if (length < 4U)
return 4U;
uint8_t audioBoost = data[0U];
uint8_t speed = data[1U];
uint16_t frequency = data[2U] * 10U;
uint8_t level = data[3U];
char ack[50U];
uint8_t n = 0U;
for (uint8_t i = 4U; i < length; i++, n++)
ack[n] = data[i];
ack[n] = '\0';
return fm.setExt(ack, audioBoost, speed, frequency, level);
}
uint8_t CSerialPort::setMode(const uint8_t* data, uint16_t length)
{ {
if (length < 1U) if (length < 1U)
return 4U; return 4U;
@ -600,7 +629,7 @@ void CSerialPort::setMode(MMDVM_STATE modemState)
void CSerialPort::start() void CSerialPort::start()
{ {
beginInt(1U, 115200); beginInt(1U, SERIAL_SPEED);
#if defined(SERIAL_REPEATER) #if defined(SERIAL_REPEATER)
beginInt(3U, 9600); beginInt(3U, 9600);
@ -618,15 +647,25 @@ void CSerialPort::process()
m_buffer[0U] = c; m_buffer[0U] = c;
m_ptr = 1U; m_ptr = 1U;
m_len = 0U; m_len = 0U;
} } else {
else {
m_ptr = 0U; m_ptr = 0U;
m_len = 0U; m_len = 0U;
} }
} else if (m_ptr == 1U) { } else if (m_ptr == 1U) {
// Handle the frame length // Handle the frame length, 1/2
m_len = m_buffer[m_ptr] = c; m_len = m_buffer[m_ptr] = c;
m_ptr = 2U; m_ptr = 2U;
} else if (m_ptr == 2U) {
// Handle the frame length, 2/2
m_buffer[m_ptr] = c;
m_ptr = 3U;
if (m_len == 0U)
m_len = c + 255U;
// The full packet has been received, process it
if (m_ptr == m_len)
processMessage(m_buffer + 3U, m_len - 3U);
} else { } else {
// Any other bytes are added to the buffer // Any other bytes are added to the buffer
m_buffer[m_ptr] = c; m_buffer[m_ptr] = c;
@ -634,6 +673,41 @@ void CSerialPort::process()
// The full packet has been received, process it // The full packet has been received, process it
if (m_ptr == m_len) { if (m_ptr == m_len) {
if (m_len > 255U)
processMessage(m_buffer + 4U, m_len - 4U);
else
processMessage(m_buffer + 3U, m_len - 3U);
}
}
}
if (io.getWatchdog() >= 48000U) {
m_ptr = 0U;
m_len = 0U;
}
#if defined(SERIAL_REPEATER)
// Write any outgoing serial data
uint16_t space = m_repeat.getData();
if (space > 0U) {
int avail = availableForWriteInt(3U);
if (avail < space)
space = avail;
for (uint16_t i = 0U; i < space; i++) {
uint8_t c = m_repeat.get();
writeInt(3U, &c, 1U);
}
}
// Read any incoming serial data
while (availableInt(3U))
readInt(3U);
#endif
}
void CSerialPort::processMessage(const uint8_t* buffer, uint16_t length)
{
uint8_t err = 2U; uint8_t err = 2U;
switch (m_buffer[2U]) { switch (m_buffer[2U]) {
@ -646,7 +720,7 @@ void CSerialPort::process()
break; break;
case MMDVM_SET_CONFIG: case MMDVM_SET_CONFIG:
err = setConfig(m_buffer + 3U, m_len - 3U); err = setConfig(buffer, length);
if (err == 0U) if (err == 0U)
sendACK(); sendACK();
else else
@ -654,7 +728,7 @@ void CSerialPort::process()
break; break;
case MMDVM_SET_MODE: case MMDVM_SET_MODE:
err = setMode(m_buffer + 3U, m_len - 3U); err = setMode(buffer, length);
if (err == 0U) if (err == 0U)
sendACK(); sendACK();
else else
@ -666,7 +740,7 @@ void CSerialPort::process()
break; break;
case MMDVM_FM_PARAMS1: case MMDVM_FM_PARAMS1:
err = setFMParams1(m_buffer + 3U, m_len - 3U); err = setFMParams1(buffer, length);
if (err == 0U) { if (err == 0U) {
sendACK(); sendACK();
} else { } else {
@ -676,7 +750,7 @@ void CSerialPort::process()
break; break;
case MMDVM_FM_PARAMS2: case MMDVM_FM_PARAMS2:
err = setFMParams2(m_buffer + 3U, m_len - 3U); err = setFMParams2(buffer, length);
if (err == 0U) { if (err == 0U) {
sendACK(); sendACK();
} else { } else {
@ -686,7 +760,7 @@ void CSerialPort::process()
break; break;
case MMDVM_FM_PARAMS3: case MMDVM_FM_PARAMS3:
err = setFMParams3(m_buffer + 3U, m_len - 3U); err = setFMParams3(buffer, length);
if (err == 0U) { if (err == 0U) {
sendACK(); sendACK();
} else { } else {
@ -695,19 +769,29 @@ void CSerialPort::process()
} }
break; break;
case MMDVM_FM_PARAMS4:
err = setFMParams4(buffer, length);
if (err == 0U) {
sendACK();
} else {
DEBUG2("Received invalid FM params 4", err);
sendNAK(err);
}
break;
case MMDVM_CAL_DATA: case MMDVM_CAL_DATA:
if (m_modemState == STATE_DSTARCAL) if (m_modemState == STATE_DSTARCAL)
err = calDStarTX.write(m_buffer + 3U, m_len - 3U); err = calDStarTX.write(buffer, length);
if (m_modemState == STATE_DMRCAL || m_modemState == STATE_LFCAL || m_modemState == STATE_DMRCAL1K || m_modemState == STATE_DMRDMO1K) if (m_modemState == STATE_DMRCAL || m_modemState == STATE_LFCAL || m_modemState == STATE_DMRCAL1K || m_modemState == STATE_DMRDMO1K)
err = calDMR.write(m_buffer + 3U, m_len - 3U); err = calDMR.write(buffer, length);
if (m_modemState == STATE_FMCAL10K || m_modemState == STATE_FMCAL12K || m_modemState == STATE_FMCAL15K || m_modemState == STATE_FMCAL20K || m_modemState == STATE_FMCAL25K || m_modemState == STATE_FMCAL30K) if (m_modemState == STATE_FMCAL10K || m_modemState == STATE_FMCAL12K || m_modemState == STATE_FMCAL15K || m_modemState == STATE_FMCAL20K || m_modemState == STATE_FMCAL25K || m_modemState == STATE_FMCAL30K)
err = calFM.write(m_buffer + 3U, m_len - 3U); err = calFM.write(buffer, length);
if (m_modemState == STATE_P25CAL1K) if (m_modemState == STATE_P25CAL1K)
err = calP25.write(m_buffer + 3U, m_len - 3U); err = calP25.write(buffer, length);
if (m_modemState == STATE_NXDNCAL1K) if (m_modemState == STATE_NXDNCAL1K)
err = calNXDN.write(m_buffer + 3U, m_len - 3U); err = calNXDN.write(buffer, length);
if (m_modemState == STATE_POCSAGCAL) if (m_modemState == STATE_POCSAGCAL)
err = calPOCSAG.write(m_buffer + 3U, m_len - 3U); err = calPOCSAG.write(buffer, length);
if (err == 0U) { if (err == 0U) {
sendACK(); sendACK();
} else { } else {
@ -719,7 +803,7 @@ void CSerialPort::process()
case MMDVM_SEND_CWID: case MMDVM_SEND_CWID:
err = 5U; err = 5U;
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
err = cwIdTX.write(m_buffer + 3U, m_len - 3U); err = cwIdTX.write(buffer, length);
if (err != 0U) { if (err != 0U) {
DEBUG2("Invalid CW Id data", err); DEBUG2("Invalid CW Id data", err);
sendNAK(err); sendNAK(err);
@ -729,7 +813,7 @@ void CSerialPort::process()
case MMDVM_DSTAR_HEADER: case MMDVM_DSTAR_HEADER:
if (m_dstarEnable) { if (m_dstarEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DSTAR) if (m_modemState == STATE_IDLE || m_modemState == STATE_DSTAR)
err = dstarTX.writeHeader(m_buffer + 3U, m_len - 3U); err = dstarTX.writeHeader(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -743,7 +827,7 @@ void CSerialPort::process()
case MMDVM_DSTAR_DATA: case MMDVM_DSTAR_DATA:
if (m_dstarEnable) { if (m_dstarEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DSTAR) if (m_modemState == STATE_IDLE || m_modemState == STATE_DSTAR)
err = dstarTX.writeData(m_buffer + 3U, m_len - 3U); err = dstarTX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -772,7 +856,7 @@ void CSerialPort::process()
if (m_dmrEnable) { if (m_dmrEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR) { if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR) {
if (m_duplex) if (m_duplex)
err = dmrTX.writeData1(m_buffer + 3U, m_len - 3U); err = dmrTX.writeData1(buffer, length);
} }
} }
if (err == 0U) { if (err == 0U) {
@ -788,9 +872,9 @@ void CSerialPort::process()
if (m_dmrEnable) { if (m_dmrEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR) { if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR) {
if (m_duplex) if (m_duplex)
err = dmrTX.writeData2(m_buffer + 3U, m_len - 3U); err = dmrTX.writeData2(buffer, length);
else else
err = dmrDMOTX.writeData(m_buffer + 3U, m_len - 3U); err = dmrDMOTX.writeData(buffer, length);
} }
} }
if (err == 0U) { if (err == 0U) {
@ -825,7 +909,7 @@ void CSerialPort::process()
case MMDVM_DMR_SHORTLC: case MMDVM_DMR_SHORTLC:
if (m_dmrEnable) if (m_dmrEnable)
err = dmrTX.writeShortLC(m_buffer + 3U, m_len - 3U); err = dmrTX.writeShortLC(buffer, length);
if (err != 0U) { if (err != 0U) {
DEBUG2("Received invalid DMR Short LC", err); DEBUG2("Received invalid DMR Short LC", err);
sendNAK(err); sendNAK(err);
@ -834,7 +918,7 @@ void CSerialPort::process()
case MMDVM_DMR_ABORT: case MMDVM_DMR_ABORT:
if (m_dmrEnable) if (m_dmrEnable)
err = dmrTX.writeAbort(m_buffer + 3U, m_len - 3U); err = dmrTX.writeAbort(buffer, length);
if (err != 0U) { if (err != 0U) {
DEBUG2("Received invalid DMR Abort", err); DEBUG2("Received invalid DMR Abort", err);
sendNAK(err); sendNAK(err);
@ -844,7 +928,7 @@ void CSerialPort::process()
case MMDVM_YSF_DATA: case MMDVM_YSF_DATA:
if (m_ysfEnable) { if (m_ysfEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_YSF) if (m_modemState == STATE_IDLE || m_modemState == STATE_YSF)
err = ysfTX.writeData(m_buffer + 3U, m_len - 3U); err = ysfTX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -858,7 +942,7 @@ void CSerialPort::process()
case MMDVM_P25_HDR: case MMDVM_P25_HDR:
if (m_p25Enable) { if (m_p25Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_P25) if (m_modemState == STATE_IDLE || m_modemState == STATE_P25)
err = p25TX.writeData(m_buffer + 3U, m_len - 3U); err = p25TX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -872,7 +956,7 @@ void CSerialPort::process()
case MMDVM_P25_LDU: case MMDVM_P25_LDU:
if (m_p25Enable) { if (m_p25Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_P25) if (m_modemState == STATE_IDLE || m_modemState == STATE_P25)
err = p25TX.writeData(m_buffer + 3U, m_len - 3U); err = p25TX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -886,7 +970,7 @@ void CSerialPort::process()
case MMDVM_NXDN_DATA: case MMDVM_NXDN_DATA:
if (m_nxdnEnable) { if (m_nxdnEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_NXDN) if (m_modemState == STATE_IDLE || m_modemState == STATE_NXDN)
err = nxdnTX.writeData(m_buffer + 3U, m_len - 3U); err = nxdnTX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -900,7 +984,7 @@ void CSerialPort::process()
case MMDVM_M17_DATA: case MMDVM_M17_DATA:
if (m_m17Enable) { if (m_m17Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_M17) if (m_modemState == STATE_IDLE || m_modemState == STATE_M17)
err = m17TX.writeData(m_buffer + 3U, m_len - 3U); err = m17TX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -914,7 +998,7 @@ void CSerialPort::process()
case MMDVM_POCSAG_DATA: case MMDVM_POCSAG_DATA:
if (m_pocsagEnable) { if (m_pocsagEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_POCSAG) if (m_modemState == STATE_IDLE || m_modemState == STATE_POCSAG)
err = pocsagTX.writeData(m_buffer + 3U, m_len - 3U); err = pocsagTX.writeData(buffer, length);
} }
if (err == 0U) { if (err == 0U) {
if (m_modemState == STATE_IDLE) if (m_modemState == STATE_IDLE)
@ -925,6 +1009,31 @@ void CSerialPort::process()
} }
break; break;
case MMDVM_FM_DATA:
if (m_fmEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_FM)
err = fm.writeData(m_buffer + 3U, m_len - 3U);
}
if (err == 0U) {
if (m_modemState == STATE_IDLE)
setMode(STATE_FM);
} else {
DEBUG2("Received invalid FM data", err);
sendNAK(err);
}
break;
case MMDVM_AX25_DATA:
if (m_ax25Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_FM)
err = ax25TX.writeData(buffer, length);
}
if (err != 0U) {
DEBUG2("Received invalid AX.25 data", err);
sendNAK(err);
}
break;
case MMDVM_TRANSPARENT: case MMDVM_TRANSPARENT:
case MMDVM_QSO_INFO: case MMDVM_QSO_INFO:
// Do nothing on the MMDVM. // Do nothing on the MMDVM.
@ -946,33 +1055,6 @@ void CSerialPort::process()
m_ptr = 0U; m_ptr = 0U;
m_len = 0U; m_len = 0U;
}
}
}
if (io.getWatchdog() >= 48000U) {
m_ptr = 0U;
m_len = 0U;
}
#if defined(SERIAL_REPEATER)
// Write any outgoing serial data
uint16_t space = m_repeat.getData();
if (space > 0U) {
int avail = availableForWriteInt(3U);
if (avail < space)
space = avail;
for (uint16_t i = 0U; i < space; i++) {
uint8_t c = m_repeat.get();
writeInt(3U, &c, 1U);
}
}
// Read any incoming serial data
while (availableInt(3U))
readInt(3U);
#endif
} }
void CSerialPort::writeDStarHeader(const uint8_t* header, uint8_t length) void CSerialPort::writeDStarHeader(const uint8_t* header, uint8_t length)
@ -1277,6 +1359,105 @@ void CSerialPort::writeM17Lost()
writeInt(1U, reply, 3); writeInt(1U, reply, 3);
} }
void CSerialPort::writeFMData(const uint8_t* data, uint16_t length)
{
if (m_modemState != STATE_FM && m_modemState != STATE_IDLE)
return;
if (!m_fmEnable)
return;
uint8_t reply[512U];
reply[0U] = MMDVM_FRAME_START;
if (length > 252U) {
reply[1U] = 0U;
reply[2U] = (length + 4U) - 255U;
reply[3U] = MMDVM_FM_DATA;
for (uint8_t i = 0U; i < length; i++)
reply[i + 4U] = data[i];
writeInt(1U, reply, length + 4U);
} else {
reply[1U] = length + 3U;
reply[2U] = MMDVM_FM_DATA;
for (uint8_t i = 0U; i < length; i++)
reply[i + 3U] = data[i];
writeInt(1U, reply, length + 3U);
}
}
void CSerialPort::writeFMStatus(uint8_t status)
{
if (m_modemState != STATE_FM && m_modemState != STATE_IDLE)
return;
if (!m_fmEnable)
return;
uint8_t reply[10U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 4U;
reply[2U] = MMDVM_FM_STATUS;
reply[3U] = status;
writeInt(1U, reply, 4U);
}
void CSerialPort::writeFMEOT()
{
if (m_modemState != STATE_FM && m_modemState != STATE_IDLE)
return;
if (!m_fmEnable)
return;
uint8_t reply[10U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 3U;
reply[2U] = MMDVM_FM_EOT;
writeInt(1U, reply, 3U);
}
void CSerialPort::writeAX25Data(const uint8_t* data, uint16_t length)
{
if (m_modemState != STATE_FM && m_modemState != STATE_IDLE)
return;
if (!m_ax25Enable)
return;
uint8_t reply[512U];
reply[0U] = MMDVM_FRAME_START;
if (length > 252U) {
reply[1U] = 0U;
reply[2U] = (length + 4U) - 255U;
reply[3U] = MMDVM_AX25_DATA;
for (uint8_t i = 0U; i < length; i++)
reply[i + 4U] = data[i];
writeInt(1U, reply, length + 4U);
} else {
reply[1U] = length + 3U;
reply[2U] = MMDVM_AX25_DATA;
for (uint8_t i = 0U; i < length; i++)
reply[i + 3U] = data[i];
writeInt(1U, reply, length + 3U);
}
}
void CSerialPort::writeCalData(const uint8_t* data, uint8_t length) void CSerialPort::writeCalData(const uint8_t* data, uint8_t length)
{ {
if (m_modemState != STATE_DSTARCAL) if (m_modemState != STATE_DSTARCAL)
@ -1446,3 +1627,4 @@ void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n
writeInt(1U, reply, count, true); writeInt(1U, reply, count, true);
} }

View File

@ -21,7 +21,11 @@
#include "Config.h" #include "Config.h"
#include "Globals.h" #include "Globals.h"
#include "SerialRB.h" #include "RingBuffer.h"
#if !defined(SERIAL_SPEED)
#define SERIAL_SPEED 115200
#endif
class CSerialPort { class CSerialPort {
@ -53,6 +57,12 @@ public:
void writeM17Data(const uint8_t* data, uint8_t length); void writeM17Data(const uint8_t* data, uint8_t length);
void writeM17Lost(); void writeM17Lost();
void writeAX25Data(const uint8_t* data, uint16_t length);
void writeFMData(const uint8_t* data, uint16_t length);
void writeFMStatus(uint8_t status);
void writeFMEOT();
void writeCalData(const uint8_t* data, uint8_t length); void writeCalData(const uint8_t* data, uint8_t length);
void writeRSSIData(const uint8_t* data, uint8_t length); void writeRSSIData(const uint8_t* data, uint8_t length);
@ -63,22 +73,24 @@ public:
void writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n3, int16_t n4); void writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n3, int16_t n4);
private: private:
uint8_t m_buffer[256U]; uint8_t m_buffer[512U];
uint8_t m_ptr; uint16_t m_ptr;
uint8_t m_len; uint16_t m_len;
bool m_debug; bool m_debug;
CSerialRB m_repeat; CRingBuffer<uint8_t> m_repeat;
void sendACK(); void sendACK();
void sendNAK(uint8_t err); void sendNAK(uint8_t err);
void getStatus(); void getStatus();
void getVersion(); void getVersion();
uint8_t setConfig(const uint8_t* data, uint8_t length); uint8_t setConfig(const uint8_t* data, uint16_t length);
uint8_t setMode(const uint8_t* data, uint8_t length); uint8_t setMode(const uint8_t* data, uint16_t length);
void setMode(MMDVM_STATE modemState); void setMode(MMDVM_STATE modemState);
uint8_t setFMParams1(const uint8_t* data, uint8_t length); uint8_t setFMParams1(const uint8_t* data, uint16_t length);
uint8_t setFMParams2(const uint8_t* data, uint8_t length); uint8_t setFMParams2(const uint8_t* data, uint16_t length);
uint8_t setFMParams3(const uint8_t* data, uint8_t length); uint8_t setFMParams3(const uint8_t* data, uint16_t length);
uint8_t setFMParams4(const uint8_t* data, uint16_t length);
void processMessage(const uint8_t* data, uint16_t length);
// Hardware versions // Hardware versions
void beginInt(uint8_t n, int speed); void beginInt(uint8_t n, int speed);

View File

@ -1,100 +0,0 @@
/*
Serial RB control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#include "SerialRB.h"
CSerialRB::CSerialRB(uint16_t length) :
m_length(length),
m_head(0U),
m_tail(0U),
m_full(false)
{
m_buffer = new uint8_t[length];
}
void CSerialRB::reset()
{
m_head = 0U;
m_tail = 0U;
m_full = false;
}
uint16_t CSerialRB::getSpace() const
{
uint16_t n = 0U;
if (m_tail == m_head)
n = m_full ? 0U : m_length;
else if (m_tail < m_head)
n = m_length - m_head + m_tail;
else
n = m_tail - m_head;
if (n > m_length)
n = 0U;
return n;
}
uint16_t CSerialRB::getData() const
{
if (m_tail == m_head)
return m_full ? m_length : 0U;
else if (m_tail < m_head)
return m_head - m_tail;
else
return m_length - m_tail + m_head;
}
bool CSerialRB::put(uint8_t c)
{
if (m_full)
return false;
m_buffer[m_head] = c;
m_head++;
if (m_head >= m_length)
m_head = 0U;
if (m_head == m_tail)
m_full = true;
return true;
}
uint8_t CSerialRB::peek() const
{
return m_buffer[m_tail];
}
uint8_t CSerialRB::get()
{
uint8_t value = m_buffer[m_tail];
m_full = false;
m_tail++;
if (m_tail >= m_length)
m_tail = 0U;
return value;
}

View File

@ -1,62 +0,0 @@
/*
Serial fifo control - Copyright (C) KI6ZUM 2015
Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Library General Public
License as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Library General Public License for more details.
You should have received a copy of the GNU Library General Public
License along with this library; if not, write to the
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
Boston, MA 02110-1301, USA.
*/
#if !defined(SERIALRB_H)
#define SERIALRB_H
#if defined(STM32F4XX)
#include "stm32f4xx.h"
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif
const uint16_t SERIAL_RINGBUFFER_SIZE = 370U;
class CSerialRB {
public:
CSerialRB(uint16_t length = SERIAL_RINGBUFFER_SIZE);
uint16_t getSpace() const;
uint16_t getData() const;
void reset();
bool put(uint8_t c);
uint8_t peek() const;
uint8_t get();
private:
uint16_t m_length;
volatile uint8_t* m_buffer;
volatile uint16_t m_head;
volatile uint16_t m_tail;
volatile bool m_full;
};
#endif

View File

@ -39,9 +39,7 @@ UART5 - TXD PC12 - RXD PD2 (Discovery, MMDVM-Pi, MMDVM-Pi F722 board, MMDVM-F4M
#if defined(STM32F4XX) || defined(STM32F7XX) #if defined(STM32F4XX) || defined(STM32F7XX)
#define TX_SERIAL_FIFO_SIZE 512U #include "STMUART.h"
#define RX_SERIAL_FIFO_SIZE 512U
extern "C" { extern "C" {
void USART1_IRQHandler(); void USART1_IRQHandler();
void USART2_IRQHandler(); void USART2_IRQHandler();
@ -52,111 +50,12 @@ extern "C" {
/* ************* USART1 ***************** */ /* ************* USART1 ***************** */
#if defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_F7M) || defined(STM32F722_PI) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || (defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)) || defined(DRCC_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446) #if defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_F7M) || defined(STM32F722_PI) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || (defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)) || defined(DRCC_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446)
volatile uint8_t TXSerialfifo1[TX_SERIAL_FIFO_SIZE];
volatile uint8_t RXSerialfifo1[RX_SERIAL_FIFO_SIZE];
volatile uint16_t TXSerialfifohead1, TXSerialfifotail1;
volatile uint16_t RXSerialfifohead1, RXSerialfifotail1;
// Init queues static CSTMUART m_USART1;
void TXSerialfifoinit1()
{
TXSerialfifohead1 = 0U;
TXSerialfifotail1 = 0U;
}
void RXSerialfifoinit1()
{
RXSerialfifohead1 = 0U;
RXSerialfifotail1 = 0U;
}
// How full is queue
// TODO decide if how full or how empty is preferred info to return
uint16_t TXSerialfifolevel1()
{
uint32_t tail = TXSerialfifotail1;
uint32_t head = TXSerialfifohead1;
if (tail > head)
return TX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
uint16_t RXSerialfifolevel1()
{
uint32_t tail = RXSerialfifotail1;
uint32_t head = RXSerialfifohead1;
if (tail > head)
return RX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
// Flushes the transmit shift register
// warning: this call is blocking
void TXSerialFlush1()
{
// wait until the TXE shows the shift register is empty
while (USART_GetITStatus(USART1, USART_FLAG_TXE))
;
}
uint8_t TXSerialfifoput1(uint8_t next)
{
if (TXSerialfifolevel1() < TX_SERIAL_FIFO_SIZE) {
TXSerialfifo1[TXSerialfifohead1] = next;
TXSerialfifohead1++;
if (TXSerialfifohead1 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifohead1 = 0U;
// make sure transmit interrupts are enabled as long as there is data to send
USART_ITConfig(USART1, USART_IT_TXE, ENABLE);
return 1U;
} else {
return 0U; // signal an overflow occurred by returning a zero count
}
}
void USART1_IRQHandler() void USART1_IRQHandler()
{ {
uint8_t c; m_USART1.handleIRQ();
if (USART_GetITStatus(USART1, USART_IT_RXNE)) {
c = (uint8_t) USART_ReceiveData(USART1);
if (RXSerialfifolevel1() < RX_SERIAL_FIFO_SIZE) {
RXSerialfifo1[RXSerialfifohead1] = c;
RXSerialfifohead1++;
if (RXSerialfifohead1 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifohead1 = 0U;
} else {
// TODO - do something if rx fifo is full?
}
USART_ClearITPendingBit(USART1, USART_IT_RXNE);
}
if (USART_GetITStatus(USART1, USART_IT_TXE)) {
c = 0U;
if (TXSerialfifohead1 != TXSerialfifotail1) { // if the fifo is not empty
c = TXSerialfifo1[TXSerialfifotail1];
TXSerialfifotail1++;
if (TXSerialfifotail1 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifotail1 = 0U;
USART_SendData(USART1, c);
} else { // if there's no more data to transmit then turn off TX interrupts
USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
}
USART_ClearITPendingBit(USART1, USART_IT_TXE);
}
} }
void InitUSART1(int speed) void InitUSART1(int speed)
@ -201,41 +100,7 @@ void InitUSART1(int speed)
USART_ITConfig(USART1, USART_IT_RXNE, ENABLE); USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
// initialize the fifos m_USART1.init(USART1);
TXSerialfifoinit1();
RXSerialfifoinit1();
}
uint8_t AvailUSART1()
{
if (RXSerialfifolevel1() > 0U)
return 1U;
else
return 0U;
}
int AvailForWriteUSART1()
{
return TX_SERIAL_FIFO_SIZE - TXSerialfifolevel1();
}
uint8_t ReadUSART1()
{
uint8_t data_c = RXSerialfifo1[RXSerialfifotail1];
RXSerialfifotail1++;
if (RXSerialfifotail1 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifotail1 = 0U;
return data_c;
}
void WriteUSART1(const uint8_t* data, uint16_t length)
{
for (uint16_t i = 0U; i < length; i++)
TXSerialfifoput1(data[i]);
USART_ITConfig(USART1, USART_IT_TXE, ENABLE);
} }
#endif #endif
@ -243,111 +108,12 @@ void WriteUSART1(const uint8_t* data, uint16_t length)
/* ************* USART2 ***************** */ /* ************* USART2 ***************** */
#if defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO) || defined(DRCC_DVM) #if defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO) || defined(DRCC_DVM)
volatile uint8_t TXSerialfifo2[TX_SERIAL_FIFO_SIZE]; static CSTMUART m_USART2;
volatile uint8_t RXSerialfifo2[RX_SERIAL_FIFO_SIZE];
volatile uint16_t TXSerialfifohead2, TXSerialfifotail2;
volatile uint16_t RXSerialfifohead2, RXSerialfifotail2;
// Init queues
void TXSerialfifoinit2()
{
TXSerialfifohead2 = 0U;
TXSerialfifotail2 = 0U;
}
void RXSerialfifoinit2()
{
RXSerialfifohead2 = 0U;
RXSerialfifotail2 = 0U;
}
// How full is queue
// TODO decide if how full or how empty is preferred info to return
uint16_t TXSerialfifolevel2()
{
uint32_t tail = TXSerialfifotail2;
uint32_t head = TXSerialfifohead2;
if (tail > head)
return TX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
uint16_t RXSerialfifolevel2()
{
uint32_t tail = RXSerialfifotail2;
uint32_t head = RXSerialfifohead2;
if (tail > head)
return RX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
// Flushes the transmit shift register
// warning: this call is blocking
void TXSerialFlush2()
{
// wait until the TXE shows the shift register is empty
while (USART_GetITStatus(USART2, USART_FLAG_TXE))
;
}
uint8_t TXSerialfifoput2(uint8_t next)
{
if (TXSerialfifolevel2() < TX_SERIAL_FIFO_SIZE) {
TXSerialfifo2[TXSerialfifohead2] = next;
TXSerialfifohead2++;
if (TXSerialfifohead2 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifohead2 = 0U;
// make sure transmit interrupts are enabled as long as there is data to send
USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
return 1U;
} else {
return 0U; // signal an overflow occurred by returning a zero count
}
}
void USART2_IRQHandler() void USART2_IRQHandler()
{ {
uint8_t c; m_USART2.handleIRQ();
if (USART_GetITStatus(USART2, USART_IT_RXNE)) {
c = (uint8_t) USART_ReceiveData(USART2);
if (RXSerialfifolevel2() < RX_SERIAL_FIFO_SIZE) {
RXSerialfifo2[RXSerialfifohead2] = c;
RXSerialfifohead2++;
if (RXSerialfifohead2 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifohead2 = 0U;
} else {
// TODO - do something if rx fifo is full?
}
USART_ClearITPendingBit(USART2, USART_IT_RXNE);
}
if (USART_GetITStatus(USART2, USART_IT_TXE)) {
c = 0U;
if (TXSerialfifohead2 != TXSerialfifotail2) { // if the fifo is not empty
c = TXSerialfifo2[TXSerialfifotail2];
TXSerialfifotail2++;
if (TXSerialfifotail2 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifotail2 = 0U;
USART_SendData(USART2, c);
} else { // if there's no more data to transmit then turn off TX interrupts
USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
}
USART_ClearITPendingBit(USART2, USART_IT_TXE);
}
} }
void InitUSART2(int speed) void InitUSART2(int speed)
@ -392,41 +158,7 @@ void InitUSART2(int speed)
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
// initialize the fifos m_USART2.init(USART2);
TXSerialfifoinit2();
RXSerialfifoinit2();
}
uint8_t AvailUSART2()
{
if (RXSerialfifolevel2() > 0U)
return 1U;
else
return 0U;
}
int AvailForWriteUSART2()
{
return TX_SERIAL_FIFO_SIZE - TXSerialfifolevel2();
}
uint8_t ReadUSART2()
{
uint8_t data_c = RXSerialfifo2[RXSerialfifotail2];
RXSerialfifotail2++;
if (RXSerialfifotail2 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifotail2 = 0U;
return data_c;
}
void WriteUSART2(const uint8_t* data, uint16_t length)
{
for (uint16_t i = 0U; i < length; i++)
TXSerialfifoput2(data[i]);
USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
} }
#endif #endif
@ -434,111 +166,11 @@ void WriteUSART2(const uint8_t* data, uint16_t length)
/* ************* USART3 ***************** */ /* ************* USART3 ***************** */
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO) #if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
volatile uint8_t TXSerialfifo3[TX_SERIAL_FIFO_SIZE]; static CSTMUART m_USART3;
volatile uint8_t RXSerialfifo3[RX_SERIAL_FIFO_SIZE];
volatile uint16_t TXSerialfifohead3, TXSerialfifotail3;
volatile uint16_t RXSerialfifohead3, RXSerialfifotail3;
// Init queues
void TXSerialfifoinit3()
{
TXSerialfifohead3 = 0U;
TXSerialfifotail3 = 0U;
}
void RXSerialfifoinit3()
{
RXSerialfifohead3 = 0U;
RXSerialfifotail3 = 0U;
}
// How full is queue
// TODO decide if how full or how empty is preferred info to return
uint16_t TXSerialfifolevel3()
{
uint32_t tail = TXSerialfifotail3;
uint32_t head = TXSerialfifohead3;
if (tail > head)
return TX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
uint16_t RXSerialfifolevel3()
{
uint32_t tail = RXSerialfifotail3;
uint32_t head = RXSerialfifohead3;
if (tail > head)
return RX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
// Flushes the transmit shift register
// warning: this call is blocking
void TXSerialFlush3()
{
// wait until the TXE shows the shift register is empty
while (USART_GetITStatus(USART3, USART_FLAG_TXE))
;
}
uint8_t TXSerialfifoput3(uint8_t next)
{
if (TXSerialfifolevel3() < TX_SERIAL_FIFO_SIZE) {
TXSerialfifo3[TXSerialfifohead3] = next;
TXSerialfifohead3++;
if (TXSerialfifohead3 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifohead3 = 0U;
// make sure transmit interrupts are enabled as long as there is data to send
USART_ITConfig(USART3, USART_IT_TXE, ENABLE);
return 1U;
} else {
return 0U; // signal an overflow occurred by returning a zero count
}
}
void USART3_IRQHandler() void USART3_IRQHandler()
{ {
uint8_t c; m_USART3.handleIRQ();
if (USART_GetITStatus(USART3, USART_IT_RXNE)) {
c = (uint8_t) USART_ReceiveData(USART3);
if (RXSerialfifolevel3() < RX_SERIAL_FIFO_SIZE) {
RXSerialfifo3[RXSerialfifohead3] = c;
RXSerialfifohead3++;
if (RXSerialfifohead3 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifohead3 = 0U;
} else {
// TODO - do something if rx fifo is full?
}
USART_ClearITPendingBit(USART3, USART_IT_RXNE);
}
if (USART_GetITStatus(USART3, USART_IT_TXE)) {
c = 0U;
if (TXSerialfifohead3 != TXSerialfifotail3) { // if the fifo is not empty
c = TXSerialfifo3[TXSerialfifotail3];
TXSerialfifotail3++;
if (TXSerialfifotail3 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifotail3 = 0U;
USART_SendData(USART3, c);
} else { // if there's no more data to transmit then turn off TX interrupts
USART_ITConfig(USART3, USART_IT_TXE, DISABLE);
}
USART_ClearITPendingBit(USART3, USART_IT_TXE);
}
} }
#if defined(STM32F7_NUCLEO) #if defined(STM32F7_NUCLEO)
@ -600,41 +232,7 @@ void InitUSART3(int speed)
USART_ITConfig(USART3, USART_IT_RXNE, ENABLE); USART_ITConfig(USART3, USART_IT_RXNE, ENABLE);
// initialize the fifos m_USART3.init(USART3);
TXSerialfifoinit3();
RXSerialfifoinit3();
}
uint8_t AvailUSART3()
{
if (RXSerialfifolevel3() > 0U)
return 1U;
else
return 0U;
}
int AvailForWriteUSART3()
{
return TX_SERIAL_FIFO_SIZE - TXSerialfifolevel3();
}
uint8_t ReadUSART3()
{
uint8_t data_c = RXSerialfifo3[RXSerialfifotail3];
RXSerialfifotail3++;
if (RXSerialfifotail3 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifotail3 = 0U;
return data_c;
}
void WriteUSART3(const uint8_t* data, uint16_t length)
{
for (uint16_t i = 0U; i < length; i++)
TXSerialfifoput3(data[i]);
USART_ITConfig(USART3, USART_IT_TXE, ENABLE);
} }
#endif #endif
@ -642,111 +240,11 @@ void WriteUSART3(const uint8_t* data, uint16_t length)
/* ************* UART5 ***************** */ /* ************* UART5 ***************** */
#if !(defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)) #if !(defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER))
volatile uint8_t TXSerialfifo5[TX_SERIAL_FIFO_SIZE]; static CSTMUART m_UART5;
volatile uint8_t RXSerialfifo5[RX_SERIAL_FIFO_SIZE];
volatile uint16_t TXSerialfifohead5, TXSerialfifotail5;
volatile uint16_t RXSerialfifohead5, RXSerialfifotail5;
// Init queues
void TXSerialfifoinit5()
{
TXSerialfifohead5 = 0U;
TXSerialfifotail5 = 0U;
}
void RXSerialfifoinit5()
{
RXSerialfifohead5 = 0U;
RXSerialfifotail5 = 0U;
}
// How full is queue
// TODO decide if how full or how empty is preferred info to return
uint16_t TXSerialfifolevel5()
{
uint32_t tail = TXSerialfifotail5;
uint32_t head = TXSerialfifohead5;
if (tail > head)
return TX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
uint16_t RXSerialfifolevel5()
{
uint32_t tail = RXSerialfifotail5;
uint32_t head = RXSerialfifohead5;
if (tail > head)
return RX_SERIAL_FIFO_SIZE + head - tail;
else
return head - tail;
}
// Flushes the transmit shift register
// warning: this call is blocking
void TXSerialFlush5()
{
// wait until the TXE shows the shift register is empty
while (USART_GetITStatus(UART5, USART_FLAG_TXE))
;
}
uint8_t TXSerialfifoput5(uint8_t next)
{
if (TXSerialfifolevel5() < TX_SERIAL_FIFO_SIZE) {
TXSerialfifo5[TXSerialfifohead5] = next;
TXSerialfifohead5++;
if (TXSerialfifohead5 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifohead5 = 0U;
// make sure transmit interrupts are enabled as long as there is data to send
USART_ITConfig(UART5, USART_IT_TXE, ENABLE);
return 1U;
} else {
return 0U; // signal an overflow occurred by returning a zero count
}
}
void UART5_IRQHandler() void UART5_IRQHandler()
{ {
uint8_t c; m_UART5.handleIRQ();
if (USART_GetITStatus(UART5, USART_IT_RXNE)) {
c = (uint8_t) USART_ReceiveData(UART5);
if (RXSerialfifolevel5() < RX_SERIAL_FIFO_SIZE) {
RXSerialfifo5[RXSerialfifohead5] = c;
RXSerialfifohead5++;
if (RXSerialfifohead5 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifohead5 = 0U;
} else {
// TODO - do something if rx fifo is full?
}
USART_ClearITPendingBit(UART5, USART_IT_RXNE);
}
if (USART_GetITStatus(UART5, USART_IT_TXE)) {
c = 0U;
if (TXSerialfifohead5 != TXSerialfifotail5) { // if the fifo is not empty
c = TXSerialfifo5[TXSerialfifotail5];
TXSerialfifotail5++;
if (TXSerialfifotail5 >= TX_SERIAL_FIFO_SIZE)
TXSerialfifotail5 = 0U;
USART_SendData(UART5, c);
} else { // if there's no more data to transmit then turn off TX interrupts
USART_ITConfig(UART5, USART_IT_TXE, DISABLE);
}
USART_ClearITPendingBit(UART5, USART_IT_TXE);
}
} }
void InitUART5(int speed) void InitUART5(int speed)
@ -795,41 +293,7 @@ void InitUART5(int speed)
USART_ITConfig(UART5, USART_IT_RXNE, ENABLE); USART_ITConfig(UART5, USART_IT_RXNE, ENABLE);
// initialize the fifos m_UART5.init(UART5);
TXSerialfifoinit5();
RXSerialfifoinit5();
}
uint8_t AvailUART5()
{
if (RXSerialfifolevel5() > 0U)
return 1U;
else
return 0U;
}
int AvailForWriteUART5()
{
return TX_SERIAL_FIFO_SIZE - TXSerialfifolevel5();
}
uint8_t ReadUART5()
{
uint8_t data_c = RXSerialfifo5[RXSerialfifotail5];
RXSerialfifotail5++;
if (RXSerialfifotail5 >= RX_SERIAL_FIFO_SIZE)
RXSerialfifotail5 = 0U;
return data_c;
}
void WriteUART5(const uint8_t* data, uint16_t length)
{
for (uint16_t i = 0U; i < length; i++)
TXSerialfifoput5(data[i]);
USART_ITConfig(UART5, USART_IT_TXE, ENABLE);
} }
#endif #endif
@ -868,21 +332,21 @@ int CSerialPort::availableInt(uint8_t n)
switch (n) { switch (n) {
case 1U: case 1U:
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO) #if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
return AvailUSART3(); return m_USART3.availble();//AvailUSART3();
#elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446)
return AvailUSART1(); return m_USART1.available();//AvailUSART1();
#elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO) #elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO)
return AvailUSART2(); return m_USART2.available();//AvailUSART2();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
return AvailUSART1(); return m_USART1.available();//AvailUSART1();
#endif #endif
case 3U: case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER) #if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
return AvailUSART1(); return m_USART1.available(); //AvailUSART1();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
return AvailUSART2(); return m_USART2.available(); //AvailUSART2();
#else #else
return AvailUART5(); return m_UART5.available();//AvailUART5();
#endif #endif
default: default:
return 0; return 0;
@ -894,21 +358,21 @@ int CSerialPort::availableForWriteInt(uint8_t n)
switch (n) { switch (n) {
case 1U: case 1U:
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO) #if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
return AvailForWriteUSART3(); return m_USART3.availableForWrite(); //AvailForWriteUSART3();
#elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446)
return AvailForWriteUSART1(); return m_USART1.availableForWrite(); //AvailForWriteUSART1();
#elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO) #elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO)
return AvailForWriteUSART2(); return m_USART2.availableForWrite();//AvailForWriteUSART2();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
return AvailForWriteUSART1(); return m_USART1.availableForWrite();//AvailForWriteUSART1();
#endif #endif
case 3U: case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER) #if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
return AvailForWriteUSART1(); return m_USART1.availableForWrite(); //AvailForWriteUSART1();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
return AvailForWriteUSART2(); return m_USART2.availableForWrite();//AvailForWriteUSART2();
#else #else
return AvailForWriteUART5(); return m_UART5.availableForWrite();//AvailForWriteUART5();
#endif #endif
default: default:
return 0; return 0;
@ -920,21 +384,21 @@ uint8_t CSerialPort::readInt(uint8_t n)
switch (n) { switch (n) {
case 1U: case 1U:
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO) #if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
return ReadUSART3(); return m_USART3.read();//ReadUSART3();
#elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446)
return ReadUSART1(); return m_USART1.read();//ReadUSART1();
#elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO) #elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO)
return ReadUSART2(); return m_USART2.read();//ReadUSART2();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
return ReadUSART1(); return m_USART1.read();//ReadUSART1();
#endif #endif
case 3U: case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER) #if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
return ReadUSART1(); return m_USART1.read();//ReadUSART1();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
return ReadUSART2(); return m_USART2.read();//ReadUSART2();
#else #else
return ReadUART5(); return m_UART5.read();//ReadUART5();
#endif #endif
default: default:
return 0U; return 0U;
@ -946,36 +410,36 @@ void CSerialPort::writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool
switch (n) { switch (n) {
case 1U: case 1U:
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO) #if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
WriteUSART3(data, length); m_USART3.write(data, length); //WriteUSART3(data, length);
if (flush) if (flush)
TXSerialFlush3(); m_USART3.flush();//TXSerialFlush3();
#elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM) || defined(STM32F4_EDA_405) || defined(STM32F4_EDA_446)
WriteUSART1(data, length); m_USART1.write(data, length);//WriteUSART1(data, length);
if (flush) if (flush)
TXSerialFlush1(); m_USART1.flush();//TXSerialFlush1();
#elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO) #elif defined(STM32F4_NUCLEO) || defined(STM32F4_RPT_HAT_TGO)
WriteUSART2(data, length); m_USART2.write(data, length);//WriteUSART2(data, length);
if (flush) if (flush)
TXSerialFlush2(); m_USART2.flush();//TXSerialFlush2();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
WriteUSART1(data, length); m_USART1.write(data, length);//WriteUSART1(data, length);
if (flush) if (flush)
TXSerialFlush1(); m_USART1.flush();//TXSerialFlush1();
#endif #endif
break; break;
case 3U: case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER) #if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
WriteUSART1(data, length); m_USART1.write(data, length); //WriteUSART1(data, length);
if (flush) if (flush)
TXSerialFlush1(); m_USART1.flush();
#elif defined(DRCC_DVM) #elif defined(DRCC_DVM)
WriteUSART2(data, length); m_USART2.write(data, length);//WriteUSART2(data, length);
if (flush) if (flush)
TXSerialFlush2(); m_USART2.flush();//TXSerialFlush2();
#else #else
WriteUART5(data, length); m_UART5.write(data, length);//WriteUART5(data, length);
if (flush) if (flush)
TXSerialFlush5(); m_UART5.flush();//TXSerialFlush5();
#endif #endif
break; break;
default: default:
@ -984,3 +448,4 @@ void CSerialPort::writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool
} }
#endif #endif

View File

@ -17,30 +17,30 @@ f2 = 2700
rp = 0.2 rp = 0.2
# scaling factor in bits, do not change ! # scaling factor in bits, do not change !
q = 0 q = 15
# scaling factor as facor... # scaling factor as facor...
scaling_factor = 2**q scaling_factor = 2**q
# let's generate a sequence of 2nd order IIR filters # let's generate a sequence of 2nd order IIR filters
sos = signal.cheby1(3,rp,[f1, f2],'bandpass', output='sos', fs=fs) sos = signal.cheby1(3,rp,[f1, f2],'bandpass', output='sos', fs=fs)
#sos = signal.cheby1(1, rp, 2122, 'lowpass', output='sos', fs=fs) #deemphasis filter #os = signal.cheby1(4, rp, f2, 'lowpass', output='sos', fs=fs) #deemphasis filter
#sos = signal.cheby1(1, rp, 2122, 'highpass', output='sos', fs=fs) #deemphasis filter #sos = signal.cheby1(1, rp, 2122, 'highpass', output='sos', fs=fs) #deemphasis filter
#sos = np.round((sos) * scaling_factor) sosrounded = np.round((sos) * scaling_factor)
# print coefficients # print coefficients
for biquad in sos: for biquad in sosrounded:
for coeff in biquad: for coeff in biquad:
#print(int(coeff),",",sep="",end="") print(int(coeff),",",sep="",end="")
print((coeff),",",sep="",end="") #print((coeff),",",sep="",end="")
print("") print("")
# plot the frequency response # plot the frequency response
b,a = signal.sos2tf(sos) b,a = signal.sos2tf(sos)
w,h = signal.freqz(b,a) w,h = signal.freqz(b,a, worN=2048)
pl.plot(w/np.pi/2*fs,20*np.log(np.abs(h))) pl.plot(w/np.pi/2*fs,20*np.log(np.abs(h)))
pl.xlabel('frequency/Hz'); pl.xlabel('frequency/Hz');
pl.ylabel('gain/dB'); pl.ylabel('gain/dB');
pl.ylim(top=1,bottom=-20); pl.ylim(top=1,bottom=-30);
pl.xlim(left=250, right=12000); pl.xlim(left=250, right=12000);
pl.show() pl.show()

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2009-2018 by Jonathan Naylor G4KLX * Copyright (C) 2009-2018,2020 by Jonathan Naylor G4KLX
* Copyright (C) 2017 by Andy Uribe CA6JAU * Copyright (C) 2017 by Andy Uribe CA6JAU
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
@ -73,7 +73,8 @@ void CYSFTX::process()
m_poBuffer[m_poLen++] = YSF_START_SYNC; m_poBuffer[m_poLen++] = YSF_START_SYNC;
} else { } else {
for (uint8_t i = 0U; i < YSF_FRAME_LENGTH_BYTES; i++) { for (uint8_t i = 0U; i < YSF_FRAME_LENGTH_BYTES; i++) {
uint8_t c = m_buffer.get(); uint8_t c = 0U;
m_buffer.get(c);
m_poBuffer[m_poLen++] = c; m_poBuffer[m_poLen++] = c;
} }
} }
@ -116,7 +117,7 @@ void CYSFTX::process()
} }
} }
uint8_t CYSFTX::writeData(const uint8_t* data, uint8_t length) uint8_t CYSFTX::writeData(const uint8_t* data, uint16_t length)
{ {
if (length != (YSF_FRAME_LENGTH_BYTES + 1U)) if (length != (YSF_FRAME_LENGTH_BYTES + 1U))
return 4U; return 4U;

View File

@ -1,5 +1,5 @@
/* /*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX * Copyright (C) 2015,2016,2017,2020 by Jonathan Naylor G4KLX
* *
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
@ -21,13 +21,13 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CYSFTX { class CYSFTX {
public: public:
CYSFTX(); CYSFTX();
uint8_t writeData(const uint8_t* data, uint8_t length); uint8_t writeData(const uint8_t* data, uint16_t length);
void process(); void process();
@ -38,7 +38,7 @@ public:
void setParams(bool on, uint8_t txHang); void setParams(bool on, uint8_t txHang);
private: private:
CSerialRB m_buffer; CRingBuffer<uint8_t> m_buffer;
arm_fir_interpolate_instance_q15 m_modFilter; arm_fir_interpolate_instance_q15 m_modFilter;
q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare q15_t m_modState[16U]; // blockSize + phaseLength - 1, 4 + 9 - 1 plus some spare
uint8_t m_poBuffer[1200U]; uint8_t m_poBuffer[1200U];