Merge branch 'FM_Ext' into AX25_FM

This commit is contained in:
Jonathan Naylor 2020-06-25 10:41:48 +01:00
commit bb66c72ef3
48 changed files with 1193 additions and 1546 deletions

View File

@ -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:

View File

@ -35,6 +35,11 @@
// 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 // Allow the use of the COS line to lockout the modem
// #define USE_COS_AS_LOCKOUT // #define USE_COS_AS_LOCKOUT

View File

@ -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];

View File

@ -23,7 +23,7 @@
#include "Config.h" #include "Config.h"
#include "DMRDefines.h" #include "DMRDefines.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CDMRDMOTX { class CDMRDMOTX {
public: public:
@ -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

@ -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 {

View File

@ -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,
@ -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

@ -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++)

View File

@ -21,7 +21,7 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CDStarTX { class CDStarTX {
public: public:
@ -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];

530
FM.cpp
View File

@ -20,9 +20,16 @@
#include "Globals.h" #include "Globals.h"
#include "FM.h" #include "FM.h"
const uint16_t FM_TX_BLOCK_SIZE = 100U;
const uint16_t FM_SERIAL_BLOCK_SIZE = 84U;//this is the number of sample pairs to send over serial. One sample pair is 3bytes.
//three times this value shall never exceed 252
const uint16_t FM_SERIAL_BLOCK_SIZE_BYTES = FM_SERIAL_BLOCK_SIZE * 3U;
CFM::CFM() : CFM::CFM() :
m_callsign(), m_callsign(),
m_rfAck(), m_rfAck(),
m_extAck(),
m_ctcssRX(), m_ctcssRX(),
m_ctcssTX(), m_ctcssTX(),
m_timeoutTone(), m_timeoutTone(),
@ -34,9 +41,11 @@ m_callsignTimer(),
m_timeoutTimer(), m_timeoutTimer(),
m_holdoffTimer(), m_holdoffTimer(),
m_kerchunkTimer(), m_kerchunkTimer(),
m_kerchunkTX(true),
m_ackMinTimer(), m_ackMinTimer(),
m_ackDelayTimer(), m_ackDelayTimer(),
m_hangTimer(), m_hangTimer(),
m_statusTimer(),
m_filterStage1( 724, 1448, 724, 32768, -37895, 21352),//3rd order Cheby Filter 300 to 2700Hz, 0.2dB passband ripple, sampling rate 24kHz m_filterStage1( 724, 1448, 724, 32768, -37895, 21352),//3rd order Cheby Filter 300 to 2700Hz, 0.2dB passband ripple, sampling rate 24kHz
m_filterStage2(32768, 0,-32768, 32768, -50339, 19052), m_filterStage2(32768, 0,-32768, 32768, -50339, 19052),
m_filterStage3(32768, -65536, 32768, 32768, -64075, 31460), m_filterStage3(32768, -65536, 32768, 32768, -64075, 31460),
@ -44,15 +53,20 @@ m_blanking(),
m_useCOS(true), m_useCOS(true),
m_cosInvert(false), m_cosInvert(false),
m_rfAudioBoost(1U), m_rfAudioBoost(1U),
m_downsampler(128U),//Size might need adjustement m_extAudioBoost(1U),
m_downsampler(400U),// 100 ms of audio
m_extEnabled(false),
m_rxLevel(1), m_rxLevel(1),
m_inputRB(4800U), // 200ms of audio m_inputRFRB(2401U), // 100ms of audio + 1 sample
m_outputRB(2400U) // 100ms of audio m_outputRFRB(2400U), // 100ms of audio
m_inputExtRB()
{ {
m_statusTimer.setTimeout(1U, 0U);
insertDelay(100U); insertDelay(100U);
} }
void CFM::samples(bool cos, const q15_t* samples, uint8_t length) void CFM::samples(bool cos, q15_t* samples, uint8_t length)
{ {
if (m_useCOS) { if (m_useCOS) {
if (m_cosInvert) if (m_cosInvert)
@ -66,74 +80,117 @@ void CFM::samples(bool cos, const q15_t* samples, uint8_t length)
uint8_t i = 0U; uint8_t i = 0U;
for (; i < length; i++) { for (; i < length; i++) {
// ARMv7-M has hardware integer division // ARMv7-M has hardware integer division
q15_t currentSample = q15_t((q31_t(samples[i]) << 8) / m_rxLevel); q15_t currentRFSample = q15_t((q31_t(samples[i]) << 8) / m_rxLevel);
uint8_t ctcssState = m_ctcssRX.process(currentRFSample);
uint8_t ctcssState = m_ctcssRX.process(currentSample);
if (!m_useCOS) { if (!m_useCOS) {
// Delay the audio by 100ms to better match the CTCSS detector output // Delay the audio by 100ms to better match the CTCSS detector output
m_inputRB.put(currentSample); m_inputRFRB.put(currentRFSample);
m_inputRB.get(currentSample); m_inputRFRB.get(currentRFSample);
} }
if (CTCSS_NOT_READY(ctcssState) && m_modemState != STATE_FM) { q15_t currentExtSample;
//Not enough samples to determine if you have CTCSS, just carry on bool inputExt = m_inputExtRB.getSample(currentExtSample);//always consume the external input data so it does not overflow
inputExt = inputExt && m_extEnabled;
if (!inputExt && (CTCSS_NOT_READY(ctcssState)) && m_modemState != STATE_FM) {
//Not enough samples to determine if you have CTCSS, just carry on. But only if we haven't any external data in the queue
continue; continue;
} else if (CTCSS_READY(ctcssState) && m_modemState != STATE_FM) { } else if ((inputExt || CTCSS_READY(ctcssState)) && m_modemState != STATE_FM) {
//we had enough samples for CTCSS and we are in some other mode than FM //we had enough samples for CTCSS and we are in some other mode than FM
bool validCTCSS = CTCSS_VALID(ctcssState); bool validCTCSS = CTCSS_VALID(ctcssState);
stateMachine(validCTCSS && cos); stateMachine(validCTCSS && cos, inputExt);
if (m_modemState != STATE_FM) if (m_modemState != STATE_FM)
continue; continue;
} else if (CTCSS_READY(ctcssState) && m_modemState == STATE_FM) { } else if ((inputExt || CTCSS_NOT_READY(ctcssState)) && m_modemState == STATE_FM && i == length - 1) {
//We had enough samples for CTCSS and we are in FM mode, trigger the state machine
bool validCTCSS = CTCSS_VALID(ctcssState);
stateMachine(validCTCSS && cos);
if (m_modemState != STATE_FM)
break;
} else if (CTCSS_NOT_READY(ctcssState) && m_modemState == STATE_FM && i == length - 1) {
//Not enough samples for CTCSS but we already are in FM, trigger the state machine //Not enough samples for CTCSS but we already are in FM, trigger the state machine
//but do not trigger the state machine on every single sample, save CPU! //but do not trigger the state machine on every single sample, save CPU!
bool validCTCSS = CTCSS_VALID(ctcssState); bool validCTCSS = CTCSS_VALID(ctcssState);
stateMachine(validCTCSS && cos); stateMachine(validCTCSS && cos, inputExt);
} }
// Only let audio through when relaying audio q15_t currentSample = currentRFSample;
if (m_state == FS_RELAYING || m_state == FS_KERCHUNK) { q15_t currentBoost = m_rfAudioBoost;
// m_downsampler.addSample(currentSample); if (m_state == FS_RELAYING_EXT || m_state == FS_KERCHUNK_EXT) {
currentSample = currentExtSample;
currentBoost = m_extAudioBoost;
}
// Only let RF audio through when relaying RF audio
if (m_state == FS_RELAYING_RF || m_state == FS_KERCHUNK_RF || m_state == FS_RELAYING_EXT || m_state == FS_KERCHUNK_EXT) {
currentSample = m_blanking.process(currentSample); currentSample = m_blanking.process(currentSample);
currentSample *= m_rfAudioBoost; if (m_extEnabled && (m_state == FS_RELAYING_RF || m_state == FS_KERCHUNK_RF))
m_downsampler.addSample(currentSample);
currentSample *= currentBoost;
} else { } else {
currentSample = 0; currentSample = 0;
} }
if (!m_callsign.isRunning()) if (!m_callsign.isRunning() && !m_extAck.isRunning())
currentSample += m_rfAck.getHighAudio(); currentSample += m_rfAck.getHighAudio();
if (!m_rfAck.isRunning()) { if (!m_callsign.isRunning() && !m_rfAck.isRunning())
currentSample += m_extAck.getHighAudio();
if (!m_rfAck.isRunning() && !m_extAck.isRunning()) {
if (m_state == FS_LISTENING) if (m_state == FS_LISTENING)
currentSample += m_callsign.getHighAudio(); currentSample += m_callsign.getHighAudio();
else else
currentSample += m_callsign.getLowAudio(); currentSample += m_callsign.getLowAudio();
} }
if (!m_callsign.isRunning() && !m_rfAck.isRunning()) if (!m_callsign.isRunning() && !m_rfAck.isRunning() && !m_extAck.isRunning())
currentSample += m_timeoutTone.getAudio(); currentSample += m_timeoutTone.getAudio();
currentSample = m_filterStage3.filter(m_filterStage2.filter(m_filterStage1.filter(currentSample))); currentSample = m_filterStage3.filter(m_filterStage2.filter(m_filterStage1.filter(currentSample)));
currentSample += m_ctcssTX.getAudio(); currentSample += m_ctcssTX.getAudio();
if (m_modemState == STATE_FM) m_outputRFRB.put(currentSample);
m_outputRB.put(currentSample);
} }
} }
void CFM::process() void CFM::process()
{ {
q15_t sample; uint16_t space = io.getSpace();
while (io.getSpace() >= 3U && m_outputRB.get(sample)) uint16_t length = m_outputRFRB.getData();
io.write(STATE_FM, &sample, 1U);
if (space > 10U && length >= FM_TX_BLOCK_SIZE ) {
space -= 2U;
if (length > FM_TX_BLOCK_SIZE)
length = FM_TX_BLOCK_SIZE;
if (space > FM_TX_BLOCK_SIZE)
space = FM_TX_BLOCK_SIZE;
if (length > space)
length = space;
q15_t samples[FM_TX_BLOCK_SIZE];
for (uint16_t i = 0U; i < length; i++) {
q15_t sample = 0;
m_outputRFRB.get(sample);
samples[i] = sample;
}
io.write(STATE_FM, samples, length);
}
if (m_extEnabled) {
uint16_t length = m_downsampler.getData();
if (length >= FM_SERIAL_BLOCK_SIZE) {
if (length > FM_SERIAL_BLOCK_SIZE)
length = FM_SERIAL_BLOCK_SIZE;
TSamplePairPack serialSamples[FM_SERIAL_BLOCK_SIZE];
for (uint16_t j = 0U; j < length; j++)
m_downsampler.getPackedData(serialSamples[j]);
serial.writeFMData((uint8_t*)serialSamples, length * sizeof(TSamplePairPack));
}
}
} }
void CFM::reset() void CFM::reset()
@ -146,13 +203,18 @@ void CFM::reset()
m_ackMinTimer.stop(); m_ackMinTimer.stop();
m_ackDelayTimer.stop(); m_ackDelayTimer.stop();
m_hangTimer.stop(); m_hangTimer.stop();
m_statusTimer.stop();
m_ctcssRX.reset(); m_ctcssRX.reset();
m_rfAck.stop(); m_rfAck.stop();
m_extAck.stop();
m_callsign.stop(); m_callsign.stop();
m_timeoutTone.stop(); m_timeoutTone.stop();
m_outputRB.reset(); m_outputRFRB.reset();
m_inputExtRB.reset();
m_downsampler.reset();
} }
uint8_t CFM::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 CFM::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)
@ -183,7 +245,7 @@ uint8_t CFM::setAck(const char* rfAck, uint8_t speed, uint16_t frequency, uint8_
return m_rfAck.setParams(rfAck, speed, frequency, level, level); return m_rfAck.setParams(rfAck, speed, frequency, level, level);
} }
uint8_t CFM::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, bool useCOS, bool cosInvert, uint8_t rfAudioBoost, uint8_t maxDev, uint8_t rxLevel) uint8_t CFM::setMisc(uint16_t timeout, uint8_t timeoutLevel, uint8_t ctcssFrequency, uint8_t ctcssHighThreshold, uint8_t ctcssLowThreshold, uint8_t ctcssLevel, uint8_t kerchunkTime, bool kerchunkTX, uint8_t hangTime, bool useCOS, bool cosInvert, uint8_t rfAudioBoost, uint8_t maxDev, uint8_t rxLevel)
{ {
m_useCOS = useCOS; m_useCOS = useCOS;
m_cosInvert = cosInvert; m_cosInvert = cosInvert;
@ -191,7 +253,10 @@ uint8_t CFM::setMisc(uint16_t timeout, uint8_t timeoutLevel, uint8_t ctcssFreque
m_rfAudioBoost = q15_t(rfAudioBoost); m_rfAudioBoost = q15_t(rfAudioBoost);
m_timeoutTimer.setTimeout(timeout, 0U); m_timeoutTimer.setTimeout(timeout, 0U);
m_kerchunkTimer.setTimeout(kerchunkTime, 0U); m_kerchunkTimer.setTimeout(kerchunkTime, 0U);
m_kerchunkTX = kerchunkTX;
m_hangTimer.setTimeout(hangTime, 0U); m_hangTimer.setTimeout(hangTime, 0U);
m_timeoutTone.setParams(timeoutLevel); m_timeoutTone.setParams(timeoutLevel);
@ -206,45 +271,61 @@ uint8_t CFM::setMisc(uint16_t timeout, uint8_t timeoutLevel, uint8_t ctcssFreque
return m_ctcssTX.setParams(ctcssFrequency, ctcssLevel); return m_ctcssTX.setParams(ctcssFrequency, ctcssLevel);
} }
void CFM::stateMachine(bool validSignal) uint8_t CFM::setExt(const char* ack, uint8_t audioBoost, uint8_t speed, uint16_t frequency, uint8_t level)
{
m_extEnabled = true;
m_extAudioBoost = q15_t(audioBoost);
return m_extAck.setParams(ack, speed, frequency, level, level);
}
void CFM::stateMachine(bool validRFSignal, bool validExtSignal)
{ {
switch (m_state) { switch (m_state) {
case FS_LISTENING: case FS_LISTENING:
listeningState(validSignal); listeningState(validRFSignal, validExtSignal);
break; break;
case FS_KERCHUNK: case FS_KERCHUNK_RF:
kerchunkState(validSignal); kerchunkRFState(validRFSignal);
break; break;
case FS_RELAYING: case FS_RELAYING_RF:
relayingState(validSignal); relayingRFState(validRFSignal);
break; break;
case FS_RELAYING_WAIT: case FS_RELAYING_WAIT_RF:
relayingWaitState(validSignal); relayingRFWaitState(validRFSignal);
break; break;
case FS_TIMEOUT: case FS_TIMEOUT_RF:
timeoutState(validSignal); timeoutRFState(validRFSignal);
break; break;
case FS_TIMEOUT_WAIT: case FS_TIMEOUT_WAIT_RF:
timeoutWaitState(validSignal); timeoutRFWaitState(validRFSignal);
break;
case FS_KERCHUNK_EXT:
kerchunkExtState(validExtSignal);
break;
case FS_RELAYING_EXT:
relayingExtState(validExtSignal);
break;
case FS_RELAYING_WAIT_EXT:
relayingExtWaitState(validExtSignal);
break;
case FS_TIMEOUT_EXT:
timeoutExtState(validExtSignal);
break;
case FS_TIMEOUT_WAIT_EXT:
timeoutExtWaitState(validExtSignal);
break; break;
case FS_HANG: case FS_HANG:
hangState(validSignal); hangState(validRFSignal, validExtSignal);
break; break;
default: default:
break; break;
} }
if (m_state == FS_LISTENING && m_modemState == STATE_FM) { if (m_state == FS_LISTENING && !m_rfAck.isWanted() && !m_extAck.isWanted() && !m_callsign.isWanted()) {
if (!m_callsign.isWanted() && !m_rfAck.isWanted()) { m_outputRFRB.reset();
DEBUG1("Change to STATE_IDLE"); m_downsampler.reset();
m_modemState = STATE_IDLE;
m_callsignTimer.stop();
m_timeoutTimer.stop();
m_kerchunkTimer.stop();
m_ackMinTimer.stop();
m_ackDelayTimer.stop();
m_hangTimer.stop();
}
} }
} }
@ -257,45 +338,90 @@ void CFM::clock(uint8_t length)
m_ackMinTimer.clock(length); m_ackMinTimer.clock(length);
m_ackDelayTimer.clock(length); m_ackDelayTimer.clock(length);
m_hangTimer.clock(length); m_hangTimer.clock(length);
m_statusTimer.clock(length);
if (m_statusTimer.isRunning() && m_statusTimer.hasExpired()) {
serial.writeFMStatus(m_state);
m_statusTimer.start();
}
} }
void CFM::listeningState(bool validSignal) void CFM::listeningState(bool validRFSignal, bool validExtSignal)
{ {
if (validSignal) { if (validRFSignal) {
if (m_kerchunkTimer.getTimeout() > 0U) { if (m_kerchunkTimer.getTimeout() > 0U) {
DEBUG1("State to KERCHUNK"); DEBUG1("State to KERCHUNK_RF");
m_state = FS_KERCHUNK; m_state = FS_KERCHUNK_RF;
m_kerchunkTimer.start(); m_kerchunkTimer.start();
if (m_callsignAtStart && !m_callsignAtLatch) if (m_callsignAtStart && !m_callsignAtLatch)
sendCallsign(); sendCallsign();
} else { } else {
DEBUG1("State to RELAYING"); DEBUG1("State to RELAYING_RF");
m_state = FS_RELAYING; m_state = FS_RELAYING_RF;
if (m_callsignAtStart) if (m_callsignAtStart)
sendCallsign(); sendCallsign();
} }
insertSilence(50U); if (m_state == FS_RELAYING_RF || (m_state == FS_KERCHUNK_RF && m_kerchunkTX)) {
insertSilence(50U);
beginRelaying(); beginRelaying();
m_callsignTimer.start(); m_callsignTimer.start();
io.setDecode(true); io.setDecode(true);
io.setADCDetection(true); io.setADCDetection(true);
DEBUG1("Change to STATE_FM"); m_statusTimer.start();
m_modemState = STATE_FM; serial.writeFMStatus(m_state);
}
} else if (validExtSignal) {
if (m_kerchunkTimer.getTimeout() > 0U) {
DEBUG1("State to KERCHUNK_EXT");
m_state = FS_KERCHUNK_EXT;
m_kerchunkTimer.start();
if (m_callsignAtStart && !m_callsignAtLatch)
sendCallsign();
} else {
DEBUG1("State to RELAYING_EXT");
m_state = FS_RELAYING_EXT;
if (m_callsignAtStart)
sendCallsign();
}
if (m_state == FS_RELAYING_EXT || (m_state == FS_KERCHUNK_EXT && m_kerchunkTX)) {
insertSilence(50U);
beginRelaying();
m_callsignTimer.start();
m_statusTimer.start();
serial.writeFMStatus(m_state);
}
} }
} }
void CFM::kerchunkState(bool validSignal) void CFM::kerchunkRFState(bool validSignal)
{ {
if (validSignal) { if (validSignal) {
if (m_kerchunkTimer.hasExpired()) { if (m_kerchunkTimer.hasExpired()) {
DEBUG1("State to RELAYING"); DEBUG1("State to RELAYING_RF");
m_state = FS_RELAYING; m_state = FS_RELAYING_RF;
m_kerchunkTimer.stop(); m_kerchunkTimer.stop();
if (!m_kerchunkTX) {
insertSilence(50U);
beginRelaying();
m_callsignTimer.start();
io.setDecode(true);
io.setADCDetection(true);
m_statusTimer.start();
serial.writeFMStatus(m_state);
}
if (m_callsignAtStart && m_callsignAtLatch) { if (m_callsignAtStart && m_callsignAtLatch) {
sendCallsign(); sendCallsign();
m_callsignTimer.start(); m_callsignTimer.start();
@ -311,26 +437,36 @@ void CFM::kerchunkState(bool validSignal)
m_timeoutTimer.stop(); m_timeoutTimer.stop();
m_ackMinTimer.stop(); m_ackMinTimer.stop();
m_callsignTimer.stop(); m_callsignTimer.stop();
m_statusTimer.stop();
if (m_extEnabled)
serial.writeFMEOT();
} }
} }
void CFM::relayingState(bool validSignal) void CFM::relayingRFState(bool validSignal)
{ {
if (validSignal) { if (validSignal) {
if (m_timeoutTimer.isRunning() && m_timeoutTimer.hasExpired()) { if (m_timeoutTimer.isRunning() && m_timeoutTimer.hasExpired()) {
DEBUG1("State to TIMEOUT"); DEBUG1("State to TIMEOUT_RF");
m_state = FS_TIMEOUT; m_state = FS_TIMEOUT_RF;
m_ackMinTimer.stop(); m_ackMinTimer.stop();
m_timeoutTimer.stop(); m_timeoutTimer.stop();
m_timeoutTone.start(); m_timeoutTone.start();
if (m_extEnabled)
serial.writeFMEOT();
} }
} else { } else {
io.setDecode(false); io.setDecode(false);
io.setADCDetection(false); io.setADCDetection(false);
DEBUG1("State to RELAYING_WAIT"); DEBUG1("State to RELAYING_WAIT_RF");
m_state = FS_RELAYING_WAIT; m_state = FS_RELAYING_WAIT_RF;
m_ackDelayTimer.start(); m_ackDelayTimer.start();
if (m_extEnabled)
serial.writeFMEOT();
} }
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) { if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) {
@ -339,14 +475,14 @@ void CFM::relayingState(bool validSignal)
} }
} }
void CFM::relayingWaitState(bool validSignal) void CFM::relayingRFWaitState(bool validSignal)
{ {
if (validSignal) { if (validSignal) {
io.setDecode(true); io.setDecode(true);
io.setADCDetection(true); io.setADCDetection(true);
DEBUG1("State to RELAYING"); DEBUG1("State to RELAYING_RF");
m_state = FS_RELAYING; m_state = FS_RELAYING_RF;
m_ackDelayTimer.stop(); m_ackDelayTimer.stop();
} else { } else {
if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) { if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) {
@ -355,12 +491,12 @@ void CFM::relayingWaitState(bool validSignal)
if (m_ackMinTimer.isRunning()) { if (m_ackMinTimer.isRunning()) {
if (m_ackMinTimer.hasExpired()) { if (m_ackMinTimer.hasExpired()) {
DEBUG1("Send ack"); DEBUG1("Send RF ack");
m_rfAck.start(); m_rfAck.start();
m_ackMinTimer.stop(); m_ackMinTimer.stop();
} }
} else { } else {
DEBUG1("Send ack"); DEBUG1("Send RF ack");
m_rfAck.start(); m_rfAck.start();
m_ackMinTimer.stop(); m_ackMinTimer.stop();
} }
@ -377,44 +513,52 @@ void CFM::relayingWaitState(bool validSignal)
} }
} }
void CFM::hangState(bool validSignal) void CFM::kerchunkExtState(bool validSignal)
{ {
if (validSignal) { if (validSignal) {
io.setDecode(true); if (m_kerchunkTimer.hasExpired()) {
io.setADCDetection(true); DEBUG1("State to RELAYING_EXT");
m_state = FS_RELAYING_EXT;
m_kerchunkTimer.stop();
if (!m_kerchunkTX) {
insertSilence(50U);
DEBUG1("State to RELAYING"); beginRelaying();
m_state = FS_RELAYING;
DEBUG1("Stop ack");
m_rfAck.stop();
beginRelaying();
} else {
if (m_hangTimer.isRunning() && m_hangTimer.hasExpired()) {
DEBUG1("State to LISTENING");
m_state = FS_LISTENING;
m_hangTimer.stop();
if (m_callsignAtEnd) m_callsignTimer.start();
m_statusTimer.start();
serial.writeFMStatus(m_state);
}
if (m_callsignAtStart && m_callsignAtLatch) {
sendCallsign(); sendCallsign();
m_callsignTimer.start();
m_callsignTimer.stop(); }
} }
} } else {
DEBUG1("State to LISTENING");
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) { m_state = FS_LISTENING;
sendCallsign(); m_kerchunkTimer.stop();
m_callsignTimer.start(); m_timeoutTimer.stop();
m_ackMinTimer.stop();
m_callsignTimer.stop();
m_statusTimer.stop();
} }
} }
void CFM::timeoutState(bool validSignal) void CFM::relayingExtState(bool validSignal)
{ {
if (!validSignal) { if (validSignal) {
io.setDecode(false); if (m_timeoutTimer.isRunning() && m_timeoutTimer.hasExpired()) {
io.setADCDetection(false); DEBUG1("State to TIMEOUT_EXT");
m_state = FS_TIMEOUT_EXT;
DEBUG1("State to TIMEOUT_WAIT"); m_ackMinTimer.stop();
m_state = FS_TIMEOUT_WAIT; m_timeoutTimer.stop();
m_timeoutTone.start();
}
} else {
DEBUG1("State to RELAYING_WAIT_EXT");
m_state = FS_RELAYING_WAIT_EXT;
m_ackDelayTimer.start(); m_ackDelayTimer.start();
} }
@ -424,21 +568,117 @@ void CFM::timeoutState(bool validSignal)
} }
} }
void CFM::timeoutWaitState(bool validSignal) void CFM::relayingExtWaitState(bool validSignal)
{
if (validSignal) {
DEBUG1("State to RELAYING_EXT");
m_state = FS_RELAYING_EXT;
m_ackDelayTimer.stop();
} else {
if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) {
DEBUG1("State to HANG");
m_state = FS_HANG;
if (m_ackMinTimer.isRunning()) {
if (m_ackMinTimer.hasExpired()) {
DEBUG1("Send Ext ack");
m_extAck.start();
m_ackMinTimer.stop();
}
} else {
DEBUG1("Send Ext ack");
m_extAck.start();
m_ackMinTimer.stop();
}
m_ackDelayTimer.stop();
m_timeoutTimer.stop();
m_hangTimer.start();
}
}
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) {
sendCallsign();
m_callsignTimer.start();
}
}
void CFM::hangState(bool validRFSignal, bool validExtSignal)
{
if (validRFSignal) {
io.setDecode(true);
io.setADCDetection(true);
DEBUG1("State to RELAYING_RF");
m_state = FS_RELAYING_RF;
DEBUG1("Stop ack");
m_rfAck.stop();
m_extAck.stop();
beginRelaying();
} else if (validExtSignal) {
DEBUG1("State to RELAYING_EXT");
m_state = FS_RELAYING_EXT;
DEBUG1("Stop ack");
m_rfAck.stop();
m_extAck.stop();
beginRelaying();
} else {
if (m_hangTimer.isRunning() && m_hangTimer.hasExpired()) {
DEBUG1("State to LISTENING");
m_state = FS_LISTENING;
m_hangTimer.stop();
m_statusTimer.stop();
if (m_callsignAtEnd)
sendCallsign();
m_callsignTimer.stop();
}
}
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) {
sendCallsign();
m_callsignTimer.start();
}
}
void CFM::timeoutRFState(bool validSignal)
{
if (!validSignal) {
io.setDecode(false);
io.setADCDetection(false);
DEBUG1("State to TIMEOUT_WAIT_RF");
m_state = FS_TIMEOUT_WAIT_RF;
if (m_callsignAtEnd)
sendCallsign();
m_ackDelayTimer.start();
}
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) {
sendCallsign();
m_callsignTimer.start();
}
}
void CFM::timeoutRFWaitState(bool validSignal)
{ {
if (validSignal) { if (validSignal) {
io.setDecode(true); io.setDecode(true);
io.setADCDetection(true); io.setADCDetection(true);
DEBUG1("State to TIMEOUT"); DEBUG1("State to TIMEOUT_RF");
m_state = FS_TIMEOUT; m_state = FS_TIMEOUT_RF;
m_ackDelayTimer.stop(); m_ackDelayTimer.stop();
} else { } else {
if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) { if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) {
DEBUG1("State to HANG"); DEBUG1("State to HANG");
m_state = FS_HANG; m_state = FS_HANG;
m_timeoutTone.stop(); m_timeoutTone.stop();
DEBUG1("Send ack"); DEBUG1("Send RF ack");
m_rfAck.start(); m_rfAck.start();
m_ackDelayTimer.stop(); m_ackDelayTimer.stop();
m_ackMinTimer.stop(); m_ackMinTimer.stop();
@ -453,6 +693,45 @@ void CFM::timeoutWaitState(bool validSignal)
} }
} }
void CFM::timeoutExtState(bool validSignal)
{
if (!validSignal) {
DEBUG1("State to TIMEOUT_WAIT_EXT");
m_state = FS_TIMEOUT_WAIT_EXT;
m_ackDelayTimer.start();
}
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) {
sendCallsign();
m_callsignTimer.start();
}
}
void CFM::timeoutExtWaitState(bool validSignal)
{
if (validSignal) {
DEBUG1("State to TIMEOUT_EXT");
m_state = FS_TIMEOUT_EXT;
m_ackDelayTimer.stop();
} else {
if (m_ackDelayTimer.isRunning() && m_ackDelayTimer.hasExpired()) {
DEBUG1("State to HANG");
m_state = FS_HANG;
m_timeoutTone.stop();
DEBUG1("Send Ext ack");
m_extAck.start();
m_ackDelayTimer.stop();
m_ackMinTimer.stop();
m_timeoutTimer.stop();
m_hangTimer.start();
}
}
if (m_callsignTimer.isRunning() && m_callsignTimer.hasExpired()) {
sendCallsign();
m_callsignTimer.start();
}
}
void CFM::sendCallsign() void CFM::sendCallsign()
{ {
if (m_holdoffTimer.isRunning()) { if (m_holdoffTimer.isRunning()) {
@ -473,12 +752,25 @@ void CFM::beginRelaying()
m_ackMinTimer.start(); m_ackMinTimer.start();
} }
uint8_t CFM::getSpace() const
{
// The amount of free space for receiving external audio, in frames.
return m_inputExtRB.getSpace() / FM_SERIAL_BLOCK_SIZE_BYTES;
}
uint8_t CFM::writeData(const uint8_t* data, uint8_t length)
{
//todo check if length is a multiple of 3
m_inputExtRB.addData(data, length);
return 0U;
}
void CFM::insertDelay(uint16_t ms) void CFM::insertDelay(uint16_t ms)
{ {
uint32_t nSamples = ms * 24U; uint32_t nSamples = ms * 24U;
for (uint32_t i = 0U; i < nSamples; i++) for (uint32_t i = 0U; i < nSamples; i++)
m_inputRB.put(0); m_inputRFRB.put(0);
} }
void CFM::insertSilence(uint16_t ms) void CFM::insertSilence(uint16_t ms)
@ -486,5 +778,5 @@ void CFM::insertSilence(uint16_t ms)
uint32_t nSamples = ms * 24U; uint32_t nSamples = ms * 24U;
for (uint32_t i = 0U; i < nSamples; i++) for (uint32_t i = 0U; i < nSamples; i++)
m_outputRB.put(0); m_outputRFRB.put(0);
} }

60
FM.h
View File

@ -27,28 +27,32 @@
#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"
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,11 +60,17 @@ 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, bool useCOS, 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, bool kerchunkTX, uint8_t hangTime, bool useCOS, bool cosInvert, 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;
CFMTimeout m_timeoutTone; CFMTimeout m_timeoutTone;
@ -72,9 +82,11 @@ private:
CFMTimer m_timeoutTimer; CFMTimer m_timeoutTimer;
CFMTimer m_holdoffTimer; CFMTimer m_holdoffTimer;
CFMTimer m_kerchunkTimer; CFMTimer m_kerchunkTimer;
bool m_kerchunkTX;
CFMTimer m_ackMinTimer; CFMTimer m_ackMinTimer;
CFMTimer m_ackDelayTimer; CFMTimer m_ackDelayTimer;
CFMTimer m_hangTimer; CFMTimer m_hangTimer;
CFMTimer m_statusTimer;
CFMDirectFormI m_filterStage1; CFMDirectFormI m_filterStage1;
CFMDirectFormI m_filterStage2; CFMDirectFormI m_filterStage2;
CFMDirectFormI m_filterStage3; CFMDirectFormI m_filterStage3;
@ -82,19 +94,27 @@ private:
bool m_useCOS; bool m_useCOS;
bool m_cosInvert; bool m_cosInvert;
q15_t m_rfAudioBoost; q15_t m_rfAudioBoost;
q15_t m_extAudioBoost;
CFMDownsampler m_downsampler; 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 listeningState(bool validRFSignal, bool validExtSignal);
void kerchunkState(bool validSignal); void kerchunkRFState(bool validSignal);
void relayingState(bool validSignal); void relayingRFState(bool validSignal);
void relayingWaitState(bool validSignal); void relayingRFWaitState(bool validSignal);
void timeoutState(bool validSignal); void timeoutRFState(bool validSignal);
void timeoutWaitState(bool validSignal); void timeoutRFWaitState(bool validSignal);
void hangState(bool validSignal); void kerchunkExtState(bool validSignal);
void relayingExtState(bool validSignal);
void relayingExtWaitState(bool validSignal);
void timeoutExtState(bool validSignal);
void timeoutExtWaitState(bool validSignal);
void hangState(bool validRFSignal, bool validExtSignal);
void clock(uint8_t length); void clock(uint8_t length);

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_

View File

@ -20,44 +20,55 @@
#include "Config.h" #include "Config.h"
#include "FMDownsampler.h" #include "FMDownsampler.h"
CFMDownsampler::CFMDownsampler(uint16_t length) : CFMDownsampler::CFMDownsampler(uint16_t length) :
m_ringBuffer(length),//length might need tweaking m_ringBuffer(length),
m_packIndex(0), m_samplePack(0U),
m_downSampleIndex(0) m_samplePackPointer(NULL),
m_sampleIndex(0U)
{ {
m_samplePack = 0; m_samplePackPointer = (uint8_t*)&m_samplePack;
} }
void CFMDownsampler::addSample(q15_t sample) void CFMDownsampler::addSample(q15_t sample)
{ {
//only take one of three samples uint32_t usample = uint32_t(int32_t(sample) + 2048);
if(m_downSampleIndex == 0) { //only take one of three samples
switch(m_packIndex){ switch(m_sampleIndex){
case 0: case 0:
m_samplePack = int32_t(sample) << 12; m_samplePack = usample << 12;
break; break;
case 1:{ case 3:{
m_samplePack |= int32_t(sample); m_samplePack |= usample;
//we did not use MSB; skip it //we did not use MSB; skip it
m_ringBuffer.put(m_samplePackBytes[1]); TSamplePairPack pair{m_samplePackPointer[0U], m_samplePackPointer[1U], m_samplePackPointer[2U]};
m_ringBuffer.put(m_samplePackBytes[2]);
m_ringBuffer.put(m_samplePackBytes[3]);
m_samplePack = 0; m_ringBuffer.put(pair);
}
break; m_samplePack = 0U;//reset the sample pack
default:
//should never happen
break;
}
m_packIndex++;
if(m_packIndex >= 2)
m_packIndex = 0;
} }
break;
default:
//Just skip this sample
break;
}
m_downSampleIndex++; m_sampleIndex++;
if(m_downSampleIndex >= 3) if(m_sampleIndex >= 6U)//did we pack two samples ?
m_downSampleIndex = 0; 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,22 @@
#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); }; bool getPackedData(TSamplePairPack& data);
inline bool hasOverflowed() { return m_ringBuffer.hasOverflowed(); }; 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

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)

15
IO.cpp
View File

@ -265,6 +265,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) {
@ -273,15 +274,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));
} }
@ -465,6 +467,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;
@ -508,9 +511,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]});
} }
} }

16
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:
@ -57,11 +61,11 @@ public:
void selfTest(); void selfTest();
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];

View File

@ -185,14 +185,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

@ -326,25 +326,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
@ -354,7 +353,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

@ -367,8 +367,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
@ -385,12 +384,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

@ -161,15 +161,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

@ -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;
} }
} }

View File

@ -21,7 +21,7 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CNXDNTX { class CNXDNTX {
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;
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;
} }
} }

View File

@ -21,7 +21,7 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CP25TX { class CP25TX {
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;
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

@ -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;
} }
} }
@ -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

@ -21,7 +21,7 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CPOCSAGTX { class CPOCSAGTX {
public: public:
@ -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

@ -70,6 +70,10 @@ 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;
@ -105,7 +109,7 @@ const uint8_t MMDVM_DEBUG5 = 0xF5U;
#define HW_TYPE "MMDVM" #define HW_TYPE "MMDVM"
#endif #endif
#define DESCRIPTION "20200624 (D-Star/DMR/System Fusion/P25/NXDN/POCSAG/FM/AX.25)" #define DESCRIPTION "20200625 (D-Star/DMR/System Fusion/P25/NXDN/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 ""
@ -160,7 +164,7 @@ 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] = 13U; reply[1U] = 15U;
reply[2U] = MMDVM_GET_STATUS; reply[2U] = MMDVM_GET_STATUS;
reply[3U] = 0x00U; reply[3U] = 0x00U;
@ -244,12 +248,17 @@ void CSerialPort::getStatus()
else else
reply[12U] = 0U; reply[12U] = 0U;
if (m_ax25Enable) if (m_fmEnable)
reply[13U] = ax25TX.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()
@ -457,12 +466,32 @@ uint8_t CSerialPort::setFMParams3(const uint8_t* data, uint16_t length)
bool useCOS = (data[8U] & 0x01U) == 0x01U; bool useCOS = (data[8U] & 0x01U) == 0x01U;
bool cosInvert = (data[8U] & 0x02U) == 0x02U; bool cosInvert = (data[8U] & 0x02U) == 0x02U;
bool kerchunkTX = (data[8U] & 0x04U) == 0x04U;
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, useCOS, cosInvert, rfAudioBoost, maxDev, rxLevel); return fm.setMisc(timeout, timeoutLevel, ctcssFrequency, ctcssHighThreshold, ctcssLowThreshold, ctcssLevel, kerchunkTime, kerchunkTX, hangTime, useCOS, cosInvert, rfAudioBoost, maxDev, rxLevel);
}
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) uint8_t CSerialPort::setMode(const uint8_t* data, uint16_t length)
@ -598,7 +627,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);
@ -738,6 +767,16 @@ void CSerialPort::processMessage(const uint8_t* buffer, uint16_t length)
} }
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(buffer, length); err = calDStarTX.write(buffer, length);
@ -954,6 +993,20 @@ void CSerialPort::processMessage(const uint8_t* buffer, uint16_t length)
} }
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: case MMDVM_AX25_DATA:
if (m_ax25Enable) { if (m_ax25Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_FM) if (m_modemState == STATE_IDLE || m_modemState == STATE_FM)
@ -1250,6 +1303,73 @@ void CSerialPort::writeNXDNLost()
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_AX25_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) void CSerialPort::writeAX25Data(const uint8_t* data, uint16_t length)
{ {
if (m_modemState != STATE_FM && m_modemState != STATE_IDLE) if (m_modemState != STATE_FM && m_modemState != STATE_IDLE)

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 {
@ -52,6 +56,10 @@ public:
void writeAX25Data(const uint8_t* data, uint16_t length); 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);
@ -66,7 +74,7 @@ private:
uint16_t m_ptr; uint16_t m_ptr;
uint16_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);
@ -78,6 +86,7 @@ private:
uint8_t setFMParams1(const uint8_t* data, uint16_t length); uint8_t setFMParams1(const uint8_t* data, uint16_t length);
uint8_t setFMParams2(const uint8_t* data, uint16_t length); uint8_t setFMParams2(const uint8_t* data, uint16_t length);
uint8_t setFMParams3(const uint8_t* data, uint16_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); void processMessage(const uint8_t* data, uint16_t length);
// Hardware versions // Hardware versions

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) #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)
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) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM)
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) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM)
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) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM)
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) #elif defined(STM32F4_PI) || defined(STM32F4_F4M) || defined(STM32F722_PI) || defined(STM32F722_F7M) || defined(STM32F722_RPT_HAT) || defined(STM32F4_DVM)
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:

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

@ -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;
} }
} }

View File

@ -21,7 +21,7 @@
#include "Config.h" #include "Config.h"
#include "SerialRB.h" #include "RingBuffer.h"
class CYSFTX { class CYSFTX {
public: public:
@ -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];