Add RSSI reporting to FM and AX.25

This commit is contained in:
Jonathan Naylor 2023-08-02 17:34:52 +01:00
parent 7ef0d992d9
commit 3e079f58ad
10 changed files with 171 additions and 30 deletions

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020,2023 by Jonathan Naylor G4KLX
* Copyright 2015-2019 Mobilinkd LLC <rob@mobilinkd.com>
*
* This program is free software; you can redistribute it and/or modify
@ -85,7 +85,9 @@ m_hdlcOnes(0U),
m_hdlcFlag(false),
m_hdlcBuffer(0U),
m_hdlcBits(0U),
m_hdlcState(AX25_IDLE)
m_hdlcState(AX25_IDLE),
m_rssiAccum(0U),
m_rssiCount(0U)
{
m_delayLine = new bool[DELAY_LEN];
@ -101,7 +103,7 @@ m_hdlcState(AX25_IDLE)
m_iirHistory[i] = 0.0F;
}
bool CAX25Demodulator::process(q15_t* samples, uint8_t length, CAX25Frame& frame)
bool CAX25Demodulator::process(q15_t* samples, const uint16_t* rssi, uint8_t length, CAX25Frame& frame)
{
bool result = false;
@ -119,6 +121,9 @@ bool CAX25Demodulator::process(q15_t* samples, uint8_t length, CAX25Frame& frame
::arm_fir_fast_q15(&m_lpfFilter, buffer, fc, RX_BLOCK_SIZE);
for (uint8_t i = 0; i < length; i++) {
m_rssiAccum += rssi[i];
m_rssiCount++;
bool bit = fc[i] >= 0;
bool sample = PLL(bit);
@ -266,6 +271,8 @@ bool CAX25Demodulator::HDLC(bool b)
// Start of frame data.
m_hdlcState = AX25_RECEIVE;
m_frame.append(m_hdlcBuffer);
m_rssiAccum = 0U;
m_rssiCount = 0U;
m_hdlcBits = 0U;
}
break;
@ -315,5 +322,19 @@ float32_t CAX25Demodulator::iir(float32_t input)
return result;
}
uint16_t CAX25Demodulator::getRSSI()
{
if (m_rssiCount > 0U) {
uint16_t rssi = m_rssiAccum / m_rssiCount;
m_rssiAccum = 0U;
m_rssiCount = 0U;
return rssi;
}
return 0U;
}
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020,2023 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
@ -36,12 +36,14 @@ class CAX25Demodulator {
public:
CAX25Demodulator(int8_t n);
bool process(q15_t* samples, uint8_t length, CAX25Frame& frame);
bool process(q15_t* samples, const uint16_t* rssi, uint8_t length, CAX25Frame& frame);
void setTwist(int8_t n);
bool isDCD();
uint16_t getRSSI();
private:
CAX25Frame m_frame;
CAX25Twist m_twist;
@ -63,6 +65,8 @@ private:
uint16_t m_hdlcBuffer;
uint16_t m_hdlcBits;
AX25_STATE m_hdlcState;
uint32_t m_rssiAccum;
uint16_t m_rssiCount;
bool delay(bool b);
bool NRZI(bool b);

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020,2023 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
@ -86,7 +86,7 @@ m_c(0xF6U)
initRand();
}
void CAX25RX::samples(q15_t* samples, uint8_t length)
void CAX25RX::samples(q15_t* samples, const uint16_t* rssi, uint8_t length)
{
q15_t output[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_filter, samples, output, RX_BLOCK_SIZE);
@ -95,32 +95,56 @@ void CAX25RX::samples(q15_t* samples, uint8_t length)
CAX25Frame frame;
bool ret = m_demod1.process(output, length, frame);
bool ret = m_demod1.process(output, rssi, length, frame);
if (ret) {
if (frame.m_fcs != m_lastFCS || m_count > 2U) {
m_lastFCS = frame.m_fcs;
m_count = 0U;
#if defined(SEND_RSSI_DATA)
uint16_t rssi = m_demod1.getRSSI();
if (rssi > 0U)
serial.writeAX25DataEx(rssi, frame.m_data, frame.m_length - 2U);
else
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
#else
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
#endif
}
DEBUG1("Decoder 1 reported");
}
ret = m_demod2.process(output, length, frame);
ret = m_demod2.process(output, rssi, length, frame);
if (ret) {
if (frame.m_fcs != m_lastFCS || m_count > 2U) {
m_lastFCS = frame.m_fcs;
m_count = 0U;
#if defined(SEND_RSSI_DATA)
uint16_t rssi = m_demod2.getRSSI();
if (rssi > 0U)
serial.writeAX25DataEx(rssi, frame.m_data, frame.m_length - 2U);
else
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
#else
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
#endif
}
DEBUG1("Decoder 2 reported");
}
ret = m_demod3.process(output, length, frame);
ret = m_demod3.process(output, rssi, length, frame);
if (ret) {
if (frame.m_fcs != m_lastFCS || m_count > 2U) {
m_lastFCS = frame.m_fcs;
m_count = 0U;
#if defined(SEND_RSSI_DATA)
uint16_t rssi = m_demod3.getRSSI();
if (rssi > 0U)
serial.writeAX25DataEx(rssi, frame.m_data, frame.m_length - 2U);
else
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
#else
serial.writeAX25Data(frame.m_data, frame.m_length - 2U);
#endif
}
DEBUG1("Decoder 3 reported");
}

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 by Jonathan Naylor G4KLX
* Copyright (C) 2020,2023 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
@ -29,7 +29,7 @@ class CAX25RX {
public:
CAX25RX();
void samples(q15_t* samples, uint8_t length);
void samples(q15_t* samples, const uint16_t* rssi, uint8_t length);
void setParams(int8_t twist, uint8_t slotTime, uint8_t pPersist);

37
FM.cpp
View File

@ -80,22 +80,24 @@ m_inputRFRB(2401U), // 100ms of audio + 1 sample
m_outputRFRB(2400U), // 100ms of audio
m_inputExtRB(),
m_rfSignal(false),
m_extSignal(false)
m_extSignal(false),
m_rssiAccum(0U),
m_rssiCount(0U)
{
m_reverseTimer.setTimeout(0U, 150U);
insertDelay(100U);
}
void CFM::samples(bool cos, q15_t* samples, uint8_t length)
void CFM::samples(bool cos, q15_t* samples, const uint16_t* rssi, uint8_t length)
{
if (m_linkMode)
linkSamples(cos, samples, length);
else
repeaterSamples(cos, samples, length);
repeaterSamples(cos, samples, rssi, length);
}
void CFM::repeaterSamples(bool cos, q15_t* samples, uint8_t length)
void CFM::repeaterSamples(bool cos, q15_t* samples, const uint16_t* rssi, uint8_t length)
{
if (m_cosInvert)
cos = !cos;
@ -104,6 +106,11 @@ void CFM::repeaterSamples(bool cos, q15_t* samples, uint8_t length)
uint8_t i = 0U;
for (; i < length; i++) {
if (m_state == FS_RELAYING_RF) {
m_rssiAccum += rssi[i];
m_rssiCount++;
}
// ARMv7-M has hardware integer division
q15_t currentRFSample = q15_t((q31_t(samples[i]) << 8) / m_rxLevel);
@ -613,6 +620,9 @@ void CFM::listeningStateDuplex(bool validRFSignal, bool validExtSignal)
m_state = FS_RELAYING_RF;
serial.writeFMStatus(m_state);
m_rssiAccum = 0U;
m_rssiCount = 0U;
if (m_callsignAtStart)
sendCallsign();
}
@ -689,6 +699,9 @@ void CFM::kerchunkRFStateDuplex(bool validSignal)
m_state = FS_RELAYING_RF;
serial.writeFMStatus(m_state);
m_rssiAccum = 0U;
m_rssiCount = 0U;
m_kerchunkTimer.stop();
if (m_callsignAtStart && m_callsignAtLatch) {
sendCallsign();
@ -716,6 +729,16 @@ void CFM::kerchunkRFStateDuplex(bool validSignal)
void CFM::relayingRFStateDuplex(bool validSignal)
{
if (validSignal) {
#if defined(SEND_RSSI_DATA)
if (m_rssiCount >= 24000U) {
uint16_t rssi = m_rssiAccum / m_rssiCount;
serial.writeFMRSSI(rssi);
m_rssiAccum = 0U;
m_rssiCount = 0U;
}
#endif
if (m_timeoutTimer.isRunning() && m_timeoutTimer.hasExpired()) {
DEBUG1("State to TIMEOUT_RF");
m_state = FS_TIMEOUT_RF;
@ -786,6 +809,9 @@ void CFM::relayingRFWaitStateDuplex(bool validSignal)
m_state = FS_RELAYING_RF;
serial.writeFMStatus(m_state);
m_rssiAccum = 0U;
m_rssiCount = 0U;
m_ackDelayTimer.stop();
} else {
if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) {
@ -977,6 +1003,9 @@ void CFM::hangStateDuplex(bool validRFSignal, bool validExtSignal)
m_state = FS_RELAYING_RF;
serial.writeFMStatus(m_state);
m_rssiAccum = 0U;
m_rssiCount = 0U;
DEBUG1("Stop ack");
m_rfAck.stop();
m_extAck.stop();

6
FM.h
View File

@ -40,7 +40,7 @@ class CFM {
public:
CFM();
void samples(bool cos, q15_t* samples, uint8_t length);
void samples(bool cos, q15_t* samples, const uint16_t* rssi, uint8_t length);
void process();
@ -94,10 +94,12 @@ private:
CFMUpSampler m_inputExtRB;
bool m_rfSignal;
bool m_extSignal;
uint32_t m_rssiAccum;
uint16_t m_rssiCount;
void stateMachine(bool validRFSignal, bool validExtSignal);
void repeaterSamples(bool cos, q15_t* samples, uint8_t length);
void repeaterSamples(bool cos, q15_t* samples, const uint16_t* rssi, uint8_t length);
void linkSamples(bool cos, q15_t* samples, uint8_t length);
void duplexStateMachine(bool validRFSignal, bool validExtSignal);

18
IO.cpp
View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015,2016,2017,2018,2020,2021 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017,2018,2020,2021,2023 by Jonathan Naylor G4KLX
* Copyright (C) 2015 by Jim Mclaughlin KI6ZUM
* Copyright (C) 2016 by Colin Durbridge G4EML
*
@ -506,9 +506,9 @@ void CIO::process()
if (m_fmEnable) {
bool cos = getCOSInt();
#if defined(USE_DCBLOCKER)
fm.samples(cos, dcSamples, RX_BLOCK_SIZE);
fm.samples(cos, dcSamples, rssi, RX_BLOCK_SIZE);
#else
fm.samples(cos, samples, RX_BLOCK_SIZE);
fm.samples(cos, samples, rssi, RX_BLOCK_SIZE);
#endif
}
#endif
@ -516,9 +516,9 @@ void CIO::process()
#if defined(MODE_FM) && defined(MODE_AX25)
if (m_ax25Enable) {
#if defined(USE_DCBLOCKER)
ax25RX.samples(dcSamples, RX_BLOCK_SIZE);
ax25RX.samples(dcSamples, rssi, RX_BLOCK_SIZE);
#else
ax25RX.samples(samples, RX_BLOCK_SIZE);
ax25RX.samples(samples, rssi, RX_BLOCK_SIZE);
#endif
}
#endif
@ -627,18 +627,18 @@ void CIO::process()
else if (m_modemState == STATE_FM) {
bool cos = getCOSInt();
#if defined(USE_DCBLOCKER)
fm.samples(cos, dcSamples, RX_BLOCK_SIZE);
fm.samples(cos, dcSamples, rssi, RX_BLOCK_SIZE);
#if defined(MODE_AX25)
if (m_ax25Enable)
ax25RX.samples(dcSamples, RX_BLOCK_SIZE);
ax25RX.samples(dcSamples, rssi, RX_BLOCK_SIZE);
#endif
#else
fm.samples(cos, samples, RX_BLOCK_SIZE);
fm.samples(cos, samples, rssi, RX_BLOCK_SIZE);
#if defined(MODE_AX25)
if (m_ax25Enable)
ax25RX.samples(samples, RX_BLOCK_SIZE);
ax25RX.samples(samples, rssi, RX_BLOCK_SIZE);
#endif
#endif
}

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2013,2015-2021 by Jonathan Naylor G4KLX
* Copyright (C) 2013,2015-2021,2023 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* This program is free software; you can redistribute it and/or modify
@ -72,6 +72,7 @@ const uint8_t MMDVM_M17_EOT = 0x49U;
const uint8_t MMDVM_POCSAG_DATA = 0x50U;
const uint8_t MMDVM_AX25_DATA = 0x55U;
const uint8_t MMDVM_AX25_DATA_EX = 0x56U;
const uint8_t MMDVM_FM_PARAMS1 = 0x60U;
const uint8_t MMDVM_FM_PARAMS2 = 0x61U;
@ -80,6 +81,7 @@ 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_FM_RSSI = 0x68U;
const uint8_t MMDVM_ACK = 0x70U;
const uint8_t MMDVM_NAK = 0x7FU;
@ -1838,6 +1840,25 @@ void CSerialPort::writeFMStatus(uint8_t status)
writeInt(1U, reply, 4U);
}
void CSerialPort::writeFMRSSI(uint16_t rssi)
{
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] = 5U;
reply[2U] = MMDVM_FM_RSSI;
reply[3U] = (rssi >> 8) & 0xFFU;
reply[4U] = (rssi >> 0) & 0xFFU;
writeInt(1U, reply, 5U);
}
void CSerialPort::writeFMEOT()
{
if (m_modemState != STATE_FM && m_modemState != STATE_IDLE)
@ -1888,6 +1909,44 @@ void CSerialPort::writeAX25Data(const uint8_t* data, uint16_t length)
writeInt(1U, reply, length + 3U);
}
}
void CSerialPort::writeAX25DataEx(uint16_t rssi, 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 > 250U) {
reply[1U] = 0U;
reply[2U] = (length + 6U) - 255U;
reply[3U] = MMDVM_AX25_DATA_EX;
reply[4U] = (rssi >> 8) & 0xFFU;
reply[5U] = (rssi >> 0) & 0xFFU;
for (uint16_t i = 0U; i < length; i++)
reply[i + 6U] = data[i];
writeInt(1U, reply, length + 6U);
} else {
reply[1U] = length + 5U;
reply[2U] = MMDVM_AX25_DATA_EX;
reply[3U] = (rssi >> 8) & 0xFFU;
reply[4U] = (rssi >> 0) & 0xFFU;
for (uint16_t i = 0U; i < length; i++)
reply[i + 5U] = data[i];
writeInt(1U, reply, length + 5U);
}
}
#endif
#if defined(SERIAL_REPEATER)

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015,2016,2017,2018,2020,2021 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017,2018,2020,2021,2023 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
@ -73,11 +73,13 @@ public:
#if defined(MODE_AX25)
void writeAX25Data(const uint8_t* data, uint16_t length);
void writeAX25DataEx(uint16_t rssi, const uint8_t* data, uint16_t length);
#endif
#if defined(MODE_FM)
void writeFMData(const uint8_t* data, uint16_t length);
void writeFMStatus(uint8_t status);
void writeFMRSSI(uint16_t rssi);
void writeFMEOT();
#endif

View File

@ -19,7 +19,7 @@
#if !defined(VERSION_H)
#define VERSION_H
#define VERSION "20230118"
#define VERSION "20230802"
#endif