Merge pull request #1 from g4klx/master

Merge with KLX Master Repo
This commit is contained in:
George Smart 2017-03-09 22:40:38 +00:00 committed by GitHub
commit 80d659d7d0
65 changed files with 7084 additions and 1357 deletions

3
.gitignore vendored Normal file
View File

@ -0,0 +1,3 @@
*.o
bin/
STM32F4XX_Lib/

View File

@ -46,8 +46,16 @@ or maybe:
"{build.variant.path}/libarm_cortexM3l_math.a"
Likely on Linux
"{build.system.path}/CMSIS/CMSIS/Lib/GCC/libarm_cortexM3l_math.a"
As with Arduino 1.6.7 with SAM 1.6.6, see below.
For Arduino 1.6.7 with SAM 1.6.6
--------------------------------
(checked OK on Arduino 1.6.11 and SAM 1.6.9)
1. Go to the where the platform.txt file is located. On my Windows machine it's
in:
@ -58,8 +66,23 @@ On Mac OS X it's located in:
/Applications/Arduino.app/Contents/Resources/Java/hardware/arduino/sam
2. You'll need to open the file in a text editor and find the line:
On Linux, it's located in my home directory, downloaded and extracted from Arduino website, but must be installed.
/home/m1geo/arduino-1.6.7/hardware/arduino/sam
or
/home/m1geo/.arduino15/packages/arduino/hardware/sam/1.6.9 (if you let the board/library manager install SAM)
I (M1GEO) found it was necessary to download SAM-1.6.6 outside of the Arduino IDE, and manually extract the files.
The Board Manager didn't seem to install the SAM files correctly. Here's how I did it:
a) wget http://downloads.arduino.cc/cores/sam-1.6.6.tar.bz2 -O /tmp/sam-1.6.6.tar.bz2 (download and save in /tmp)
b) cd arduino-1.6.7/hardware/arduino/ (Arduino root, here, in my home directory)
c) tar xvfj /tmp/sam-1.6.6.tar.bz2
2. You'll need to open the file (platform.txt) in a text editor and find the line:
## Combine gc-sections, archives, and objects
recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" -mcpu={build.mcu} -mthumb {compiler.c.elf.flags} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--start-group "{build.path}/core/syscalls_sam3.c.o" {object_files} "{build.variant.path}/{build.variant_system_lib}" "{build.path}/{archive_file}" -Wl,--end-group -lm -gcc
@ -68,7 +91,6 @@ In my version it's line 73.
3. Modify it to read as follows:
## Combine gc-sections, archives, and objects
recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" -mcpu={build.mcu} -mthumb {compiler.c.elf.flags} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--start-group "{build.path}/core/syscalls_sam3.c.o" {object_files} "{build.variant.path}/{build.variant_system_lib}" "{build.system.path}/CMSIS/CMSIS/Lib/ARM/arm_cortexM3l_math.lib" "{build.path}/{archive_file}" -Wl,--end-group -lm -gcc
@ -76,15 +98,28 @@ The change is near the end, and is the addition of:
"{build.system.path}/CMSIS/CMSIS/Lib/ARM/arm_cortexM3l_math.lib"
On Linux, the path was found to differ slightly (GCC instead of ARM):
"{build.system.path}/CMSIS/CMSIS/Lib/GCC/libarm_cortexM3l_math.a"
Which is the CMSIS AMR3 DSP library for little-endian operation.
4. Save the file and start up the Arduino GUI and build MMDVM.
I would like to get instructions for doing the same on a Linux platform. As a
starter find the relevent platform.txt and try adding:
For Arduino 1.6.9 with SAM 1.6.8
--------------------------------
"{build.system.path}/CMSIS/CMSIS/Lib/ARM/libarm_cortexM3l_math.a"
1. Locate platform.txt. On Ubuntu 14.04 LTS x86_64 OS it is in:
or maybe:
/home/$user/.arduino15/packages/arduino/hardware/sam/1.6.8/
"{build.variant.path}/libarm_cortexM3l_math.a"
2. Open the file in a text editor and change the line:
## Combine gc-sections, archives, and objects
recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" -mcpu={build.mcu} -mthumb {compiler.c.elf.flags} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--start-group {compiler.combine.flags} {object_files} "{build.variant.path}/{build.variant_system_lib}" "{build.path}/{archive_file}" -Wl,--end-group -lm -gcc
to
recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" -mcpu={build.mcu} -mthumb {compiler.c.elf.flags} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--start-group {compiler.combine.flags} {object_files} "{build.variant.path}/{build.variant_system_lib}" "{build.system.path}/CMSIS/CMSIS/Lib/GCC/libarm_cortexM3l_math.a" "{build.path}/{archive_file}" -Wl,--end-group -lm -gcc
3. Save the file, open the Arduino IDE and build MMDVM

173
CWIdTX.cpp Normal file
View File

@ -0,0 +1,173 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "CWIdTX.h"
q15_t TONE[] = {
0, 518, 1000, 1414, 1732, 1932, 2000, 1932, 1732, 1414, 1000, 518, 0, -518, -1000, -1414, -1732, -1932, -2000, -1932, -1732, -1414, -1000, -518};
q15_t SILENCE[] = {
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
const uint8_t CYCLE_LENGTH = 24U;
const uint8_t DOT_LENGTH = 50U;
const struct {
uint8_t c;
uint32_t pattern;
uint8_t length;
} SYMBOL_LIST[] = {
{'A', 0xB8000000U, 8U},
{'B', 0xEA800000U, 12U},
{'C', 0xEBA00000U, 14U},
{'D', 0xEA000000U, 10U},
{'E', 0x80000000U, 4U},
{'F', 0xAE800000U, 12U},
{'G', 0xEE800000U, 12U},
{'H', 0xAA000000U, 10U},
{'I', 0xA0000000U, 6U},
{'J', 0xBBB80000U, 16U},
{'K', 0xEB800000U, 12U},
{'L', 0xBA800000U, 12U},
{'M', 0xEE000000U, 10U},
{'N', 0xE8000000U, 8U},
{'O', 0xEEE00000U, 14U},
{'P', 0xBBA00000U, 14U},
{'Q', 0xEEB80000U, 16U},
{'R', 0xBA000000U, 10U},
{'S', 0xA8000000U, 8U},
{'T', 0xE0000000U, 6U},
{'U', 0xAE000000U, 10U},
{'V', 0xAB800000U, 12U},
{'W', 0xBB800000U, 12U},
{'X', 0xEAE00000U, 14U},
{'Y', 0xEBB80000U, 16U},
{'Z', 0xEEA00000U, 14U},
{'1', 0xBBBB8000U, 20U},
{'2', 0xAEEE0000U, 18U},
{'3', 0xABB80000U, 16U},
{'4', 0xAAE00000U, 14U},
{'5', 0xAA800000U, 12U},
{'6', 0xEAA00000U, 14U},
{'7', 0xEEA80000U, 16U},
{'8', 0xEEEA0000U, 18U},
{'9', 0xEEEE8000U, 20U},
{'0', 0xEEEEE000U, 22U},
{'/', 0xEAE80000U, 16U},
{'?', 0xAEEA0000U, 18U},
{',', 0xEEAEE000U, 22U},
{' ', 0x00000000U, 4U},
{0U, 0x00000000U, 0U}
};
const uint8_t BIT_MASK_TABLE[] = {0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02U, 0x01U};
#define WRITE_BIT1(p,i,b) p[(i)>>3] = (b) ? (p[(i)>>3] | BIT_MASK_TABLE[(i)&7]) : (p[(i)>>3] & ~BIT_MASK_TABLE[(i)&7])
#define READ_BIT1(p,i) (p[(i)>>3] & BIT_MASK_TABLE[(i)&7])
CCWIdTX::CCWIdTX() :
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U),
m_n(0U)
{
}
void CCWIdTX::process()
{
if (m_poLen == 0U)
return;
uint16_t space = io.getSpace();
while (space > CYCLE_LENGTH) {
bool b = READ_BIT1(m_poBuffer, m_poPtr);
if (b)
io.write(STATE_CWID, TONE, CYCLE_LENGTH);
else
io.write(STATE_CWID, SILENCE, CYCLE_LENGTH);
space -= CYCLE_LENGTH;
m_n++;
if (m_n >= DOT_LENGTH) {
m_poPtr++;
m_n = 0U;
}
if (m_poPtr >= m_poLen) {
m_poPtr = 0U;
m_poLen = 0U;
return;
}
}
}
uint8_t CCWIdTX::write(const uint8_t* data, uint8_t length)
{
::memset(m_poBuffer, 0x00U, 1000U * sizeof(uint8_t));
m_poLen = 8U;
m_poPtr = 0U;
m_n = 0U;
for (uint8_t i = 0U; i < length; i++) {
for (uint8_t j = 0U; SYMBOL_LIST[j].c != 0U; j++) {
if (SYMBOL_LIST[j].c == data[i]) {
uint32_t MASK = 0x80000000U;
for (uint8_t k = 0U; k < SYMBOL_LIST[j].length; k++, m_poLen++, MASK >>= 1) {
bool b = (SYMBOL_LIST[j].pattern & MASK) == MASK;
WRITE_BIT1(m_poBuffer, m_poLen, b);
if (m_poLen >= 995U) {
m_poLen = 0U;
return 4U;
}
}
break;
}
}
}
// An empty message
if (m_poLen == 8U) {
m_poLen = 0U;
return 4U;
}
m_poLen += 5U;
DEBUG2("Message created with length", m_poLen);
return 0U;
}
void CCWIdTX::reset()
{
m_poLen = 0U;
m_poPtr = 0U;
m_n = 0U;
}

43
CWIdTX.h Normal file
View File

@ -0,0 +1,43 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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(CWIDTX_H)
#define CWIDTX_H
#include "Config.h"
class CCWIdTX {
public:
CCWIdTX();
void process();
uint8_t write(const uint8_t* data, uint8_t length);
void reset();
private:
uint8_t m_poBuffer[1000U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint8_t m_n;
};
#endif

49
CalDMR.cpp Normal file
View File

@ -0,0 +1,49 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "CalDMR.h"
CCalDMR::CCalDMR() :
m_transmit(false)
{
}
void CCalDMR::process()
{
if (m_transmit) {
dmrTX.setCal(true);
dmrTX.process();
} else {
dmrTX.setCal(false);
}
}
uint8_t CCalDMR::write(const uint8_t* data, uint8_t length)
{
if (length != 1U)
return 4U;
m_transmit = data[0U] == 1U;
return 0U;
}

39
CalDMR.h Normal file
View File

@ -0,0 +1,39 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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(CALDMR_H)
#define CALDMR_H
#include "Config.h"
#include "DMRDefines.h"
class CCalDMR {
public:
CCalDMR();
void process();
uint8_t write(const uint8_t* data, uint8_t length);
private:
bool m_transmit;
};
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -18,7 +18,7 @@
#include "Config.h"
#include "Globals.h"
#include "CalRX.h"
#include "CalDStarRX.h"
#include "Utils.h"
const unsigned int BUFFER_LENGTH = 200U;
@ -33,7 +33,7 @@ const uint32_t DATA_SYNC_DATA2 = 0x00554B97U;
const uint32_t DATA_SYNC_MASK = 0x00FFFFFFU;
const uint8_t DATA_SYNC_ERRS = 2U;
CCalRX::CCalRX() :
CCalDStarRX::CCalDStarRX() :
m_pll(0U),
m_prev(false),
m_patternBuffer(0x00U),
@ -42,7 +42,7 @@ m_ptr(0U)
{
}
void CCalRX::samples(const q15_t* samples, uint8_t length)
void CCalDStarRX::samples(const q15_t* samples, uint8_t length)
{
for (uint16_t i = 0U; i < length; i++) {
bool bit = samples[i] < 0;
@ -65,7 +65,7 @@ void CCalRX::samples(const q15_t* samples, uint8_t length)
}
}
void CCalRX::process(q15_t value)
void CCalDStarRX::process(q15_t value)
{
m_patternBuffer <<= 1;
if (value < 0)

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,15 +16,15 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(CALRX_H)
#define CALRX_H
#if !defined(CALDSTARRX_H)
#define CALDSTARRX_H
#include "Config.h"
#include "DStarDefines.h"
class CCalRX {
class CCalDStarRX {
public:
CCalRX();
CCalDStarRX();
void samples(const q15_t* samples, uint8_t length);

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -18,7 +18,7 @@
#include "Config.h"
#include "Globals.h"
#include "CalTX.h"
#include "CalDStarTX.h"
const uint8_t HEADER[] = {0x00U, 0x00U, 0x00U, 'D', 'I', 'R', 'E', 'C', 'T', ' ', ' ',
'D', 'I', 'R', 'E', 'C', 'T', ' ', ' ',
@ -28,13 +28,13 @@ const uint8_t HEADER[] = {0x00U, 0x00U, 0x00U, 'D', 'I', 'R', 'E', 'C', 'T', ' '
const uint8_t SLOW_DATA_TEXT[] = {'M', 'M', 'D', 'V', 'M', ' ', 'M', 'o', 'd', 'e', 'm', ' ', 'T', 'e', 's', 't', ' ', ' ', ' ', ' '};
CCalTX::CCalTX() :
CCalDStarTX::CCalDStarTX() :
m_transmit(false),
m_count(0U)
{
}
void CCalTX::process()
void CCalDStarTX::process()
{
dstarTX.process();
@ -162,7 +162,7 @@ void CCalTX::process()
m_count = (m_count + 1U) % (30U * 21U);
}
uint8_t CCalTX::write(const uint8_t* data, uint8_t length)
uint8_t CCalDStarTX::write(const uint8_t* data, uint8_t length)
{
if (length != 1U)
return 4U;

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,15 +16,15 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(CALTX_H)
#define CALTX_H
#if !defined(CALDSTARTX_H)
#define CALDSTARTX_H
#include "Config.h"
#include "DStarDefines.h"
class CCalTX {
class CCalDStarTX {
public:
CCalTX();
CCalDStarTX();
uint8_t write(const uint8_t* data, uint8_t length);

65
CalRSSI.cpp Normal file
View File

@ -0,0 +1,65 @@
/*
* Copyright (C) 2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "CalRSSI.h"
#include "Utils.h"
CCalRSSI::CCalRSSI() :
m_count(0U),
m_accum(0U),
m_min(0xFFFFU),
m_max(0x0000U)
{
}
void CCalRSSI::samples(const uint16_t* rssi, uint8_t length)
{
for (uint16_t i = 0U; i < length; i++) {
uint16_t ss = rssi[i];
m_accum += ss;
if (ss > m_max)
m_max = ss;
if (ss < m_min)
m_min = ss;
m_count++;
if (m_count >= 24000U) {
uint16_t ave = m_accum / m_count;
uint8_t buffer[6U];
buffer[0U] = (m_max >> 8) & 0xFFU;
buffer[1U] = (m_max >> 0) & 0xFFU;
buffer[2U] = (m_min >> 8) & 0xFFU;
buffer[3U] = (m_min >> 0) & 0xFFU;
buffer[4U] = (ave >> 8) & 0xFFU;
buffer[5U] = (ave >> 0) & 0xFFU;
serial.writeRSSIData(buffer, 6U);
m_count = 0U;
m_accum = 0U;
m_min = 0xFFFFU;
m_max = 0x0000U;
}
}
}

38
CalRSSI.h Normal file
View File

@ -0,0 +1,38 @@
/*
* Copyright (C) 2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(CALRSSI_H)
#define CALRSSI_H
#include "Config.h"
class CCalRSSI {
public:
CCalRSSI();
void samples(const uint16_t* rssi, uint8_t length);
private:
uint32_t m_count;
uint32_t m_accum;
uint16_t m_min;
uint16_t m_max;
};
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -19,16 +19,53 @@
#if !defined(CONFIG_H)
#define CONFIG_H
// #define WANT_DEBUG
// Allow for the use of high quality external clock oscillators
// The number is the frequency of the oscillator in Hertz.
//
// The frequency of the TCXO must be an integer multiple of 48000.
// Frequencies such as 12.0 Mhz (48000 * 250) and 14.4 Mhz (48000 * 300) are suitable.
// Frequencies such as 10.0 Mhz (48000 * 208.333) or 20 Mhz (48000 * 416.666) are not suitable.
//
// For 12 MHz
// #define EXTERNAL_OSC 12000000
// For 12.288 MHz
// #define EXTERNAL_OSC 12288000
// For 14.4 MHz
// #define EXTERNAL_OSC 14400000
// For 19.2 MHz
// #define EXTERNAL_OSC 19200000
// Allow the use of the COS line to lockout the modem
// #define USE_COS_AS_LOCKOUT
// Use pins to output the current mode
// #define ARDUINO_MODE_PINS
// For the original Arduino Due pin layout
#define ARDUINO_DUE_PAPA
// #define ARDUINO_DUE_PAPA
// For the new Arduino Due pin layout
// #define ARDUINO_DUE_ZUM
// For the ZUM V1.0 and V1.0.1 boards pin layout
#define ARDUINO_DUE_ZUM_V10
// For the SP8NTH board
// #define ARDUINO_DUE_NTH
// #define ARDUINO_DUE_NTH
// For ST Nucleo-64 STM32F446RE board
// #define STM32F4_NUCLEO_MORPHO_HEADER
// #define STM32F4_NUCLEO_ARDUINO_HEADER
// Use separate mode pins to switch external filters/bandwidth for example
// #define STM32F4_NUCLEO_MODE_PINS
// To use wider C4FSK filters for DMR, System Fusion and P25 on transmit
// #define WIDE_C4FSK_FILTERS_TX
// To use wider C4FSK filters for DMR, System Fusion and P25 on receive
// #define WIDE_C4FSK_FILTERS_RX
// Pass RSSI information to the host
// #define SEND_RSSI_DATA
// Use the modem as a serial repeater for Nextion displays
// #define SERIAL_REPEATER
#endif

473
DMRDMORX.cpp Normal file
View File

@ -0,0 +1,473 @@
/*
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#define WANT_DEBUG
// #define DUMP_SAMPLES
#include "Config.h"
#include "Globals.h"
#include "DMRDMORX.h"
#include "DMRSlotType.h"
#include "Utils.h"
const q15_t SCALING_FACTOR = 19505; // Q15(0.60)
const uint8_t MAX_SYNC_SYMBOLS_ERRS = 2U;
const uint8_t MAX_SYNC_BYTES_ERRS = 3U;
const uint8_t MAX_SYNC_LOST_FRAMES = 13U;
const uint8_t BIT_MASK_TABLE[] = {0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02U, 0x01U};
#define WRITE_BIT1(p,i,b) p[(i)>>3] = (b) ? (p[(i)>>3] | BIT_MASK_TABLE[(i)&7]) : (p[(i)>>3] & ~BIT_MASK_TABLE[(i)&7])
const uint16_t NOENDPTR = 9999U;
const uint8_t CONTROL_NONE = 0x00U;
const uint8_t CONTROL_VOICE = 0x20U;
const uint8_t CONTROL_DATA = 0x40U;
CDMRDMORX::CDMRDMORX() :
m_bitBuffer(),
m_buffer(),
m_bitPtr(0U),
m_dataPtr(0U),
m_syncPtr(0U),
m_startPtr(0U),
m_endPtr(NOENDPTR),
m_maxCorr(0),
m_centre(),
m_threshold(),
m_averagePtr(0U),
m_control(CONTROL_NONE),
m_syncCount(0U),
m_colorCode(0U),
m_state(DMORXS_NONE),
m_n(0U),
m_type(0U),
m_rssi()
{
}
void CDMRDMORX::reset()
{
m_syncPtr = 0U;
m_maxCorr = 0;
m_control = CONTROL_NONE;
m_syncCount = 0U;
m_state = DMORXS_NONE;
m_startPtr = 0U;
m_endPtr = NOENDPTR;
}
void CDMRDMORX::samples(const q15_t* samples, const uint16_t* rssi, uint8_t length)
{
bool dcd = false;
for (uint8_t i = 0U; i < length; i++)
dcd = processSample(samples[i], rssi[i]);
io.setDecode(dcd);
}
bool CDMRDMORX::processSample(q15_t sample, uint16_t rssi)
{
m_buffer[m_dataPtr] = sample;
m_rssi[m_dataPtr] = rssi;
m_bitBuffer[m_bitPtr] <<= 1;
if (sample < 0)
m_bitBuffer[m_bitPtr] |= 0x01U;
if (m_state == DMORXS_NONE) {
correlateSync(true);
} else {
uint16_t min = m_syncPtr + DMO_BUFFER_LENGTH_SAMPLES - 1U;
uint16_t max = m_syncPtr + 1U;
if (min >= DMO_BUFFER_LENGTH_SAMPLES)
min -= DMO_BUFFER_LENGTH_SAMPLES;
if (max >= DMO_BUFFER_LENGTH_SAMPLES)
max -= DMO_BUFFER_LENGTH_SAMPLES;
if (min < max) {
if (m_dataPtr >= min && m_dataPtr <= max)
correlateSync(false);
} else {
if (m_dataPtr >= min || m_dataPtr <= max)
correlateSync(false);
}
}
if (m_dataPtr == m_endPtr) {
// Find the average centre and threshold values
q15_t centre = (m_centre[0U] + m_centre[1U] + m_centre[2U] + m_centre[3U]) >> 2;
q15_t threshold = (m_threshold[0U] + m_threshold[1U] + m_threshold[2U] + m_threshold[3U]) >> 2;
uint8_t frame[DMR_FRAME_LENGTH_BYTES + 3U];
frame[0U] = m_control;
uint16_t ptr = m_endPtr + DMO_BUFFER_LENGTH_SAMPLES - DMR_FRAME_LENGTH_SAMPLES + DMR_RADIO_SYMBOL_LENGTH + 1U;
if (ptr >= DMO_BUFFER_LENGTH_SAMPLES)
ptr -= DMO_BUFFER_LENGTH_SAMPLES;
samplesToBits(ptr, DMR_FRAME_LENGTH_SYMBOLS, frame, 8U, centre, threshold);
if (m_control == CONTROL_DATA) {
// Data sync
uint8_t colorCode;
uint8_t dataType;
CDMRSlotType slotType;
slotType.decode(frame + 1U, colorCode, dataType);
if (colorCode == m_colorCode) {
m_syncCount = 0U;
m_n = 0U;
frame[0U] |= dataType;
switch (dataType) {
case DT_DATA_HEADER:
DEBUG4("DMRDMORX: data header found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMORXS_DATA;
m_type = 0x00U;
break;
case DT_RATE_12_DATA:
case DT_RATE_34_DATA:
case DT_RATE_1_DATA:
if (m_state == DMORXS_DATA) {
DEBUG4("DMRDMORX: data payload found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_type = dataType;
}
break;
case DT_VOICE_LC_HEADER:
DEBUG4("DMRDMORX: voice header found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMORXS_VOICE;
break;
case DT_VOICE_PI_HEADER:
if (m_state == DMORXS_VOICE) {
DEBUG4("DMRDMORX: voice pi header found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
}
m_state = DMORXS_VOICE;
break;
case DT_TERMINATOR_WITH_LC:
if (m_state == DMORXS_VOICE) {
DEBUG4("DMRDMORX: voice terminator found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
reset();
}
break;
default: // DT_CSBK
DEBUG4("DMRDMORX: csbk found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
reset();
break;
}
}
} else if (m_control == CONTROL_VOICE) {
// Voice sync
DEBUG4("DMRDMORX: voice sync found pos/centre/threshold", m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMORXS_VOICE;
m_syncCount = 0U;
m_n = 0U;
} else {
if (m_state != DMORXS_NONE) {
m_syncCount++;
if (m_syncCount >= MAX_SYNC_LOST_FRAMES) {
serial.writeDMRLost(true);
reset();
}
}
if (m_state == DMORXS_VOICE) {
if (m_n >= 5U) {
frame[0U] = CONTROL_VOICE;
m_n = 0U;
} else {
frame[0U] = ++m_n;
}
serial.writeDMRData(true, frame, DMR_FRAME_LENGTH_BYTES + 1U);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
} else if (m_state == DMORXS_DATA) {
if (m_type != 0x00U) {
frame[0U] = CONTROL_DATA | m_type;
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
}
}
}
// End of this slot, reset some items for the next slot.
m_maxCorr = 0;
m_control = CONTROL_NONE;
}
m_dataPtr++;
if (m_dataPtr >= DMO_BUFFER_LENGTH_SAMPLES)
m_dataPtr = 0U;
m_bitPtr++;
if (m_bitPtr >= DMR_RADIO_SYMBOL_LENGTH)
m_bitPtr = 0U;
return m_state != DMORXS_NONE;
}
void CDMRDMORX::correlateSync(bool first)
{
uint8_t errs = countBits32((m_bitBuffer[m_bitPtr] & DMR_SYNC_SYMBOLS_MASK) ^ DMR_MS_DATA_SYNC_SYMBOLS);
// The voice sync is the complement of the data sync
bool data = (errs <= MAX_SYNC_SYMBOLS_ERRS);
bool voice = (errs >= (DMR_SYNC_LENGTH_SYMBOLS - MAX_SYNC_SYMBOLS_ERRS));
if (data || voice) {
uint16_t ptr = m_dataPtr + DMO_BUFFER_LENGTH_SAMPLES - DMR_SYNC_LENGTH_SAMPLES + DMR_RADIO_SYMBOL_LENGTH;
if (ptr >= DMO_BUFFER_LENGTH_SAMPLES)
ptr -= DMO_BUFFER_LENGTH_SAMPLES;
q31_t corr = 0;
q15_t min = 16000;
q15_t max = -16000;
for (uint8_t i = 0U; i < DMR_SYNC_LENGTH_SYMBOLS; i++) {
q15_t val = m_buffer[ptr];
if (val > max)
max = val;
if (val < min)
min = val;
int8_t corrVal;
if (data)
corrVal = DMR_MS_DATA_SYNC_SYMBOLS_VALUES[i];
else
corrVal = DMR_MS_VOICE_SYNC_SYMBOLS_VALUES[i];
switch (corrVal) {
case +3:
corr -= (val + val + val);
break;
case +1:
corr -= val;
break;
case -1:
corr += val;
break;
default: // -3
corr += (val + val + val);
break;
}
ptr += DMR_RADIO_SYMBOL_LENGTH;
if (ptr >= DMO_BUFFER_LENGTH_SAMPLES)
ptr -= DMO_BUFFER_LENGTH_SAMPLES;
}
if (corr > m_maxCorr) {
q15_t centre = (max + min) >> 1;
q31_t v1 = (max - centre) * SCALING_FACTOR;
q15_t threshold = q15_t(v1 >> 15);
uint8_t sync[DMR_SYNC_BYTES_LENGTH];
uint16_t ptr = m_dataPtr + DMO_BUFFER_LENGTH_SAMPLES - DMR_SYNC_LENGTH_SAMPLES + DMR_RADIO_SYMBOL_LENGTH;
if (ptr >= DMO_BUFFER_LENGTH_SAMPLES)
ptr -= DMO_BUFFER_LENGTH_SAMPLES;
samplesToBits(ptr, DMR_SYNC_LENGTH_SYMBOLS, sync, 4U, centre, threshold);
if (data) {
uint8_t errs = 0U;
for (uint8_t i = 0U; i < DMR_SYNC_BYTES_LENGTH; i++)
errs += countBits8((sync[i] & DMR_SYNC_BYTES_MASK[i]) ^ DMR_MS_DATA_SYNC_BYTES[i]);
if (errs <= MAX_SYNC_BYTES_ERRS) {
if (first) {
m_threshold[0U] = m_threshold[1U] = m_threshold[2U] = m_threshold[3U] = threshold;
m_centre[0U] = m_centre[1U] = m_centre[2U] = m_centre[3U] = centre;
m_averagePtr = 0U;
} else {
m_threshold[m_averagePtr] = threshold;
m_centre[m_averagePtr] = centre;
m_averagePtr++;
if (m_averagePtr >= 4U)
m_averagePtr = 0U;
}
m_maxCorr = corr;
m_control = CONTROL_DATA;
m_syncPtr = m_dataPtr;
m_startPtr = m_dataPtr + DMO_BUFFER_LENGTH_SAMPLES - DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U - DMR_INFO_LENGTH_SAMPLES / 2U - DMR_SYNC_LENGTH_SAMPLES;
if (m_startPtr >= DMO_BUFFER_LENGTH_SAMPLES)
m_startPtr -= DMO_BUFFER_LENGTH_SAMPLES;
m_endPtr = m_dataPtr + DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U + DMR_INFO_LENGTH_SAMPLES / 2U - 1U;
if (m_endPtr >= DMO_BUFFER_LENGTH_SAMPLES)
m_endPtr -= DMO_BUFFER_LENGTH_SAMPLES;
}
} else { // if (voice1 || voice2)
uint8_t errs = 0U;
for (uint8_t i = 0U; i < DMR_SYNC_BYTES_LENGTH; i++)
errs += countBits8((sync[i] & DMR_SYNC_BYTES_MASK[i]) ^ DMR_MS_VOICE_SYNC_BYTES[i]);
if (errs <= MAX_SYNC_BYTES_ERRS) {
if (first) {
m_threshold[0U] = m_threshold[1U] = m_threshold[2U] = m_threshold[3U] = threshold;
m_centre[0U] = m_centre[1U] = m_centre[2U] = m_centre[3U] = centre;
m_averagePtr = 0U;
} else {
m_threshold[m_averagePtr] = threshold;
m_centre[m_averagePtr] = centre;
m_averagePtr++;
if (m_averagePtr >= 4U)
m_averagePtr = 0U;
}
m_maxCorr = corr;
m_control = CONTROL_VOICE;
m_syncPtr = m_dataPtr;
m_startPtr = m_dataPtr + DMO_BUFFER_LENGTH_SAMPLES - DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U - DMR_INFO_LENGTH_SAMPLES / 2U - DMR_SYNC_LENGTH_SAMPLES;
if (m_startPtr >= DMO_BUFFER_LENGTH_SAMPLES)
m_startPtr -= DMO_BUFFER_LENGTH_SAMPLES;
m_endPtr = m_dataPtr + DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U + DMR_INFO_LENGTH_SAMPLES / 2U - 1U;
if (m_endPtr >= DMO_BUFFER_LENGTH_SAMPLES)
m_endPtr -= DMO_BUFFER_LENGTH_SAMPLES;
}
}
}
}
}
void CDMRDMORX::samplesToBits(uint16_t start, uint8_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold)
{
for (uint8_t i = 0U; i < count; i++) {
q15_t sample = m_buffer[start] - centre;
if (sample < -threshold) {
WRITE_BIT1(buffer, offset, false);
offset++;
WRITE_BIT1(buffer, offset, true);
offset++;
} else if (sample < 0) {
WRITE_BIT1(buffer, offset, false);
offset++;
WRITE_BIT1(buffer, offset, false);
offset++;
} else if (sample < threshold) {
WRITE_BIT1(buffer, offset, true);
offset++;
WRITE_BIT1(buffer, offset, false);
offset++;
} else {
WRITE_BIT1(buffer, offset, true);
offset++;
WRITE_BIT1(buffer, offset, true);
offset++;
}
start += DMR_RADIO_SYMBOL_LENGTH;
if (start >= DMO_BUFFER_LENGTH_SAMPLES)
start -= DMO_BUFFER_LENGTH_SAMPLES;
}
}
void CDMRDMORX::setColorCode(uint8_t colorCode)
{
m_colorCode = colorCode;
}
void CDMRDMORX::writeRSSIData(uint8_t* frame)
{
#if defined(SEND_RSSI_DATA)
// Calculate RSSI average over a burst period. We don't take into account 2.5 ms at the beginning and 2.5 ms at the end
uint16_t start = m_startPtr + DMR_SYNC_LENGTH_SAMPLES / 2U;
uint32_t accum = 0U;
for (uint16_t i = 0U; i < (DMR_FRAME_LENGTH_SAMPLES - DMR_SYNC_LENGTH_SAMPLES); i++) {
accum += m_rssi[start];
start++;
if (start >= DMO_BUFFER_LENGTH_SAMPLES)
start -= DMO_BUFFER_LENGTH_SAMPLES;
}
uint16_t avg = accum / (DMR_FRAME_LENGTH_SAMPLES - DMR_SYNC_LENGTH_SAMPLES);
frame[34U] = (avg >> 8) & 0xFFU;
frame[35U] = (avg >> 0) & 0xFFU;
serial.writeDMRData(true, frame, DMR_FRAME_LENGTH_BYTES + 3U);
#else
serial.writeDMRData(true, frame, DMR_FRAME_LENGTH_BYTES + 1U);
#endif
}
#if defined(DUMP_SAMPLES)
void CDMRDMORX::writeSamples(uint16_t start, uint8_t control)
{
q15_t samples[DMR_FRAME_LENGTH_SYMBOLS];
for (uint16_t i = 0U; i < DMR_FRAME_LENGTH_SYMBOLS; i++) {
samples[i] = m_buffer[start];
start += DMR_RADIO_SYMBOL_LENGTH;
if (start >= DMO_BUFFER_LENGTH_SAMPLES)
start -= DMO_BUFFER_LENGTH_SAMPLES;
}
serial.writeSamples(STATE_DMR, control, samples, DMR_FRAME_LENGTH_SYMBOLS);
}
#endif

70
DMRDMORX.h Normal file
View File

@ -0,0 +1,70 @@
/*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(DMRDMORX_H)
#define DMRDMORX_H
#include "Config.h"
#include "DMRDefines.h"
const uint16_t DMO_BUFFER_LENGTH_SAMPLES = 1440U; // 60ms at 24 kHz
enum DMORX_STATE {
DMORXS_NONE,
DMORXS_VOICE,
DMORXS_DATA
};
class CDMRDMORX {
public:
CDMRDMORX();
void samples(const q15_t* samples, const uint16_t* rssi, uint8_t length);
void setColorCode(uint8_t colorCode);
void reset();
private:
uint32_t m_bitBuffer[DMR_RADIO_SYMBOL_LENGTH];
q15_t m_buffer[DMO_BUFFER_LENGTH_SAMPLES];
uint16_t m_bitPtr;
uint16_t m_dataPtr;
uint16_t m_syncPtr;
uint16_t m_startPtr;
uint16_t m_endPtr;
q31_t m_maxCorr;
q15_t m_centre[4U];
q15_t m_threshold[4U];
uint8_t m_averagePtr;
uint8_t m_control;
uint8_t m_syncCount;
uint8_t m_colorCode;
DMORX_STATE m_state;
uint8_t m_n;
uint8_t m_type;
uint16_t m_rssi[DMO_BUFFER_LENGTH_SAMPLES];
bool processSample(q15_t sample, uint16_t rssi);
void correlateSync(bool first);
void samplesToBits(uint16_t start, uint8_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void writeRSSIData(uint8_t* frame);
void writeSamples(uint16_t start, uint8_t control);
};
#endif

170
DMRDMOTX.cpp Normal file
View File

@ -0,0 +1,170 @@
/*
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "DMRSlotType.h"
#if defined(WIDE_C4FSK_FILTERS_TX)
// Generated using rcosdesign(0.2, 4, 5, 'sqrt') in MATLAB
static q15_t DMR_C4FSK_FILTER[] = {688, -680, -2158, -3060, -2724, -775, 2684, 7041, 11310, 14425, 15565, 14425,
11310, 7041, 2684, -775, -2724, -3060, -2158, -680, 688, 0};
const uint16_t DMR_C4FSK_FILTER_LEN = 22U;
#else
// Generated using rcosdesign(0.2, 8, 5, 'sqrt') in MATLAB
static q15_t DMR_C4FSK_FILTER[] = {401, 104, -340, -731, -847, -553, 112, 909, 1472, 1450, 683, -675, -2144, -3040, -2706, -770, 2667, 6995,
11237, 14331, 15464, 14331, 11237, 6995, 2667, -770, -2706, -3040, -2144, -675, 683, 1450, 1472, 909, 112,
-553, -847, -731, -340, 104, 401, 0};
const uint16_t DMR_C4FSK_FILTER_LEN = 42U;
#endif
const q15_t DMR_LEVELA[] = { 640, 640 , 640, 640, 640};
const q15_t DMR_LEVELB[] = { 213, 213, 213, 213, 213};
const q15_t DMR_LEVELC[] = {-213, -213, -213, -213, -213};
const q15_t DMR_LEVELD[] = {-640, -640, -640, -640, -640};
CDMRDMOTX::CDMRDMOTX() :
m_fifo(),
m_modFilter(),
m_modState(),
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U),
m_txDelay(240U), // 200ms
m_count(0U)
{
::memset(m_modState, 0x00U, 70U * sizeof(q15_t));
m_modFilter.numTaps = DMR_C4FSK_FILTER_LEN;
m_modFilter.pState = m_modState;
m_modFilter.pCoeffs = DMR_C4FSK_FILTER;
}
void CDMRDMOTX::process()
{
if (m_poLen == 0U && m_fifo.getData() > 0U) {
if (!m_tx) {
for (uint16_t i = 0U; i < m_txDelay; i++)
m_poBuffer[m_poLen++] = 0x00U;
} else {
for (unsigned int i = 0U; i < 72U; i++)
m_poBuffer[m_poLen++] = 0x00U;
for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++)
m_poBuffer[i] = m_fifo.get();
}
m_poPtr = 0U;
}
if (m_poLen > 0U) {
uint16_t space = io.getSpace();
while (space > (4U * DMR_RADIO_SYMBOL_LENGTH)) {
uint8_t c = m_poBuffer[m_poPtr++];
writeByte(c);
space -= 4U * DMR_RADIO_SYMBOL_LENGTH;
if (m_poPtr >= m_poLen) {
m_poPtr = 0U;
m_poLen = 0U;
return;
}
}
}
}
uint8_t CDMRDMOTX::writeData(const uint8_t* data, uint8_t length)
{
if (length != (DMR_FRAME_LENGTH_BYTES + 1U))
return 4U;
uint16_t space = m_fifo.getSpace();
if (space < DMR_FRAME_LENGTH_BYTES)
return 5U;
for (uint8_t i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++)
m_fifo.put(data[i + 1U]);
return 0U;
}
void CDMRDMOTX::writeByte(uint8_t c)
{
q15_t inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U + 1U];
q15_t outBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U + 1U];
const uint8_t MASK = 0xC0U;
q15_t* p = inBuffer;
for (uint8_t i = 0U; i < 4U; i++, c <<= 2, p += DMR_RADIO_SYMBOL_LENGTH) {
switch (c & MASK) {
case 0xC0U:
::memcpy(p, DMR_LEVELA, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x80U:
::memcpy(p, DMR_LEVELB, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x00U:
::memcpy(p, DMR_LEVELC, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
default:
::memcpy(p, DMR_LEVELD, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
}
}
uint16_t blockSize = DMR_RADIO_SYMBOL_LENGTH * 4U;
// Handle the case of the oscillator not being accurate enough
if (m_sampleCount > 0U) {
m_count += DMR_RADIO_SYMBOL_LENGTH * 4U;
if (m_count >= m_sampleCount) {
if (m_sampleInsert) {
inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U] = inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U - 1U];
blockSize++;
} else {
blockSize--;
}
m_count -= m_sampleCount;
}
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, blockSize);
io.write(STATE_DMR, outBuffer, blockSize);
}
uint16_t CDMRDMOTX::getSpace() const
{
return m_fifo.getSpace() / (DMR_FRAME_LENGTH_BYTES + 2U);
}
void CDMRDMOTX::setTXDelay(uint8_t delay)
{
m_txDelay = 600U + uint16_t(delay) * 12U; // 500ms + tx delay
}

54
DMRDMOTX.h Normal file
View File

@ -0,0 +1,54 @@
/*
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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(DMRDMOTX_H)
#define DMRDMOTX_H
#include "Config.h"
#include "DMRDefines.h"
#include "SerialRB.h"
class CDMRDMOTX {
public:
CDMRDMOTX();
uint8_t writeData(const uint8_t* data, uint8_t length);
void process();
void setTXDelay(uint8_t delay);
uint16_t getSpace() const;
private:
CSerialRB m_fifo;
arm_fir_instance_q15 m_modFilter;
q15_t m_modState[70U]; // NoTaps + BlockSize - 1, 42 + 20 - 1 plus some spare
uint8_t m_poBuffer[1200U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint16_t m_txDelay;
uint32_t m_count;
void writeByte(uint8_t c);
};
#endif

View File

@ -35,6 +35,10 @@ const unsigned int DMR_EMB_LENGTH_BITS = 16U;
const unsigned int DMR_EMB_LENGTH_SYMBOLS = 8U;
const unsigned int DMR_EMB_LENGTH_SAMPLES = DMR_EMB_LENGTH_SYMBOLS * DMR_RADIO_SYMBOL_LENGTH;
const unsigned int DMR_EMBSIG_LENGTH_BITS = 32U;
const unsigned int DMR_EMBSIG_LENGTH_SYMBOLS = 16U;
const unsigned int DMR_EMBSIG_LENGTH_SAMPLES = DMR_EMBSIG_LENGTH_SYMBOLS * DMR_RADIO_SYMBOL_LENGTH;
const unsigned int DMR_SLOT_TYPE_LENGTH_BITS = 20U;
const unsigned int DMR_SLOT_TYPE_LENGTH_SYMBOLS = 10U;
const unsigned int DMR_SLOT_TYPE_LENGTH_SAMPLES = DMR_SLOT_TYPE_LENGTH_SYMBOLS * DMR_RADIO_SYMBOL_LENGTH;
@ -71,13 +75,27 @@ const uint32_t DMR_BS_DATA_SYNC_SYMBOLS = 0x00439B4DU;
const uint32_t DMR_BS_VOICE_SYNC_SYMBOLS = 0x00BC64B2U;
const uint32_t DMR_SYNC_SYMBOLS_MASK = 0x00FFFFFFU;
// D 5 D 7 F 7 7 F D 7 5 7
// 11 01 01 01 11 01 01 11 11 11 01 11 01 11 11 11 11 01 01 11 01 01 01 11
// -3 +3 +3 +3 -3 +3 +3 -3 -3 -3 +3 -3 +3 -3 -3 -3 -3 +3 +3 -3 +3 +3 +3 -3
const int8_t DMR_MS_DATA_SYNC_SYMBOLS_VALUES[] = {-3, +3, +3, +3, -3, +3, +3, -3, -3, -3, +3, -3, +3, -3, -3, -3, -3, +3, +3, -3, +3, +3, +3, -3};
// 7 F 7 D 5 D D 5 7 D F D
// 01 11 11 11 01 11 11 01 01 01 11 01 11 01 01 01 01 11 11 01 11 11 11 01
// +3 -3 -3 -3 +3 -3 -3 +3 +3 +3 -3 +3 -3 +3 +3 +3 +3 -3 -3 +3 -3 -3 -3 +3
const int8_t DMR_MS_VOICE_SYNC_SYMBOLS_VALUES[] = {+3, -3, -3, -3, +3, -3, -3, +3, +3, +3, -3, +3, -3, +3, +3, +3, +3, -3, -3, +3, -3, -3, -3, +3};
const uint8_t DT_VOICE_PI_HEADER = 0U;
const uint8_t DT_VOICE_LC_HEADER = 1U;
const uint8_t DT_TERMINATOR_WITH_LC = 2U;
const uint8_t DT_CSBK = 3U;
const uint8_t DT_DATA_HEADER = 6U;
const uint8_t DT_RATE_12_DATA = 7U;
const uint8_t DT_RATE_34_DATA = 8U;
const uint8_t DT_IDLE = 9U;
// All others are for data transfer
const uint8_t DT_RATE_1_DATA = 10U;
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,6 +16,10 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#define WANT_DEBUG
// #define DUMP_SAMPLES
#include "Config.h"
#include "Globals.h"
#include "DMRIdleRX.h"
@ -31,12 +35,17 @@ const uint8_t BIT_MASK_TABLE[] = {0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02
#define WRITE_BIT1(p,i,b) p[(i)>>3] = (b) ? (p[(i)>>3] | BIT_MASK_TABLE[(i)&7]) : (p[(i)>>3] & ~BIT_MASK_TABLE[(i)&7])
const uint16_t NOENDPTR = 9999U;
const uint8_t CONTROL_IDLE = 0x80U;
const uint8_t CONTROL_DATA = 0x40U;
CDMRIdleRX::CDMRIdleRX() :
m_bitBuffer(),
m_buffer(),
m_bitPtr(0U),
m_dataPtr(0U),
m_endPtr(999U),
m_endPtr(NOENDPTR),
m_maxCorr(0),
m_centre(0),
m_threshold(0),
@ -51,7 +60,7 @@ void CDMRIdleRX::reset()
m_maxCorr = 0;
m_threshold = 0;
m_centre = 0;
m_endPtr = 999U;
m_endPtr = NOENDPTR;
}
void CDMRIdleRX::samples(const q15_t* samples, uint8_t length)
@ -77,16 +86,28 @@ void CDMRIdleRX::processSample(q15_t sample)
q15_t max = -16000;
q15_t min = 16000;
uint32_t mask = 0x00800000U;
for (uint8_t i = 0U; i < DMR_SYNC_LENGTH_SYMBOLS; i++, mask >>= 1) {
bool b = (DMR_MS_DATA_SYNC_SYMBOLS & mask) == mask;
for (uint8_t i = 0U; i < DMR_SYNC_LENGTH_SYMBOLS; i++) {
q15_t val = m_buffer[ptr];
if (m_buffer[ptr] > max)
max = m_buffer[ptr];
if (m_buffer[ptr] < min)
min = m_buffer[ptr];
if (val > max)
max = val;
if (val < min)
min = val;
corr += b ? -m_buffer[ptr] : m_buffer[ptr];
switch (DMR_MS_DATA_SYNC_SYMBOLS_VALUES[i]) {
case +3:
corr -= (val + val + val);
break;
case +1:
corr -= val;
break;
case -1:
corr += val;
break;
default: // -3
corr += (val + val + val);
break;
}
ptr += DMR_RADIO_SYMBOL_LENGTH;
if (ptr >= DMR_FRAME_LENGTH_SAMPLES)
@ -138,16 +159,15 @@ void CDMRIdleRX::processSample(q15_t sample)
slotType.decode(frame + 1U, colorCode, dataType);
if (colorCode == m_colorCode && dataType == DT_CSBK) {
frame[0U] = 0x80U | 0x40U | DT_CSBK; // Idle RX, Data Sync, CSBK
frame[0U] = CONTROL_IDLE | CONTROL_DATA | DT_CSBK;
serial.writeDMRData(false, frame, DMR_FRAME_LENGTH_BYTES + 1U);
#if defined(WANT_DEBUG)
} else {
DEBUG5("DMRIdleRX: invalid color code or data type", colorCode, m_colorCode, dataType, DT_CSBK);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
}
m_endPtr = 999U;
m_maxCorr = 0U;
m_endPtr = NOENDPTR;
m_maxCorr = 0;
}
m_dataPtr++;
@ -197,3 +217,19 @@ void CDMRIdleRX::setColorCode(uint8_t colorCode)
m_colorCode = colorCode;
}
#if defined(DUMP_SAMPLES)
void CDMRIdleRX::writeSamples(uint16_t start, uint8_t control)
{
q15_t samples[DMR_FRAME_LENGTH_SYMBOLS];
for (uint16_t i = 0U; i < DMR_FRAME_LENGTH_SYMBOLS; i++) {
samples[i] = m_buffer[start];
start += DMR_RADIO_SYMBOL_LENGTH;
if (start >= DMR_FRAME_LENGTH_SAMPLES)
start -= DMR_FRAME_LENGTH_SAMPLES;
}
serial.writeSamples(STATE_DMR, control, samples, DMR_FRAME_LENGTH_SYMBOLS);
}
#endif

View File

@ -43,8 +43,9 @@ private:
q15_t m_threshold;
uint8_t m_colorCode;
void processSample(q15_t sample);
void samplesToBits(uint16_t start, uint8_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void processSample(q15_t sample);
void samplesToBits(uint16_t start, uint8_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void writeSamples(uint16_t start, uint8_t control);
};
#endif

View File

@ -26,7 +26,7 @@ m_slot2RX(true)
{
}
void CDMRRX::samples(const q15_t* samples, const uint8_t* control, uint8_t length)
void CDMRRX::samples(const q15_t* samples, const uint16_t* rssi, const uint8_t* control, uint8_t length)
{
bool dcd1 = false;
bool dcd2 = false;
@ -43,8 +43,8 @@ void CDMRRX::samples(const q15_t* samples, const uint8_t* control, uint8_t lengt
break;
}
dcd1 = m_slot1RX.processSample(samples[i]);
dcd2 = m_slot2RX.processSample(samples[i]);
dcd1 = m_slot1RX.processSample(samples[i], rssi[i]);
dcd2 = m_slot2RX.processSample(samples[i], rssi[i]);
}
io.setDecode(dcd1 || dcd2);
@ -56,6 +56,12 @@ void CDMRRX::setColorCode(uint8_t colorCode)
m_slot2RX.setColorCode(colorCode);
}
void CDMRRX::setDelay(uint8_t delay)
{
m_slot1RX.setDelay(delay);
m_slot2RX.setDelay(delay);
}
void CDMRRX::reset()
{
m_slot1RX.reset();

View File

@ -26,9 +26,10 @@ class CDMRRX {
public:
CDMRRX();
void samples(const q15_t* samples, const uint8_t* control, uint8_t length);
void samples(const q15_t* samples, const uint16_t* rssi, const uint8_t* control, uint8_t length);
void setColorCode(uint8_t colorCode);
void setDelay(uint8_t delay);
void reset();

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,12 +16,19 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#define WANT_DEBUG
// #define DUMP_SAMPLES
#include "Config.h"
#include "Globals.h"
#include "DMRSlotRX.h"
#include "DMRSlotType.h"
#include "Utils.h"
const uint16_t SCAN_START = 400U;
const uint16_t SCAN_END = 490U;
const q15_t SCALING_FACTOR = 19505; // Q15(0.60)
const uint8_t MAX_SYNC_SYMBOLS_ERRS = 2U;
@ -35,6 +42,10 @@ const uint8_t BIT_MASK_TABLE[] = {0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02
const uint16_t NOENDPTR = 9999U;
const uint8_t CONTROL_NONE = 0x00U;
const uint8_t CONTROL_VOICE = 0x20U;
const uint8_t CONTROL_DATA = 0x40U;
CDMRSlotRX::CDMRSlotRX(bool slot) :
m_slot(slot),
m_bitBuffer(),
@ -42,69 +53,87 @@ m_buffer(),
m_bitPtr(0U),
m_dataPtr(0U),
m_syncPtr(0U),
m_startPtr(0U),
m_endPtr(NOENDPTR),
m_delayPtr(0U),
m_maxCorr(0),
m_centre(0),
m_threshold(0),
m_control(0x00U),
m_centre(),
m_threshold(),
m_averagePtr(0U),
m_control(CONTROL_NONE),
m_syncCount(0U),
m_colorCode(0U),
m_n(0U)
m_delay(0U),
m_state(DMRRXS_NONE),
m_n(0U),
m_type(0U),
m_rssi()
{
}
void CDMRSlotRX::start()
{
m_dataPtr = 0U;
m_bitPtr = 0U;
m_maxCorr = 0;
m_control = 0x00U;
m_dataPtr = 0U;
m_delayPtr = 0U;
m_bitPtr = 0U;
m_maxCorr = 0;
m_control = CONTROL_NONE;
}
void CDMRSlotRX::reset()
{
m_syncPtr = 0U;
m_dataPtr = 0U;
m_delayPtr = 0U;
m_bitPtr = 0U;
m_maxCorr = 0;
m_control = 0x00U;
m_control = CONTROL_NONE;
m_syncCount = 0U;
m_threshold = 0;
m_centre = 0;
m_state = DMRRXS_NONE;
m_startPtr = 0U;
m_endPtr = NOENDPTR;
}
bool CDMRSlotRX::processSample(q15_t sample)
bool CDMRSlotRX::processSample(q15_t sample, uint16_t rssi)
{
m_delayPtr++;
if (m_delayPtr < m_delay)
return m_state != DMRRXS_NONE;
// Ensure that the buffer doesn't overflow
if (m_dataPtr > m_endPtr || m_dataPtr >= 900U)
return m_endPtr != NOENDPTR;
return m_state != DMRRXS_NONE;
m_buffer[m_dataPtr] = sample;
m_rssi[m_dataPtr] = rssi;
m_bitBuffer[m_bitPtr] <<= 1;
if (sample < 0)
m_bitBuffer[m_bitPtr] |= 0x01U;
// The approximate position of the sync samples
if (m_endPtr != NOENDPTR) {
uint16_t min = m_syncPtr - 5U;
uint16_t max = m_syncPtr + 5U;
if (m_dataPtr >= min && m_dataPtr <= max)
correlateSync(sample);
if (m_state == DMRRXS_NONE) {
if (m_dataPtr >= SCAN_START && m_dataPtr <= SCAN_END)
correlateSync(true);
} else {
if (m_dataPtr >= 390U && m_dataPtr <= 500U)
correlateSync(sample);
uint16_t min = m_syncPtr - 1U;
uint16_t max = m_syncPtr + 1U;
if (m_dataPtr >= min && m_dataPtr <= max)
correlateSync(false);
}
if (m_dataPtr == m_endPtr) {
uint8_t frame[DMR_FRAME_LENGTH_BYTES + 1U];
// Find the average centre and threshold values
q15_t centre = (m_centre[0U] + m_centre[1U] + m_centre[2U] + m_centre[3U]) >> 2;
q15_t threshold = (m_threshold[0U] + m_threshold[1U] + m_threshold[2U] + m_threshold[3U]) >> 2;
uint8_t frame[DMR_FRAME_LENGTH_BYTES + 3U];
frame[0U] = m_control;
uint16_t ptr = m_endPtr - DMR_FRAME_LENGTH_SAMPLES + DMR_RADIO_SYMBOL_LENGTH + 1U;
samplesToBits(ptr, DMR_FRAME_LENGTH_SYMBOLS, frame, 8U, m_centre, m_threshold);
samplesToBits(ptr, DMR_FRAME_LENGTH_SYMBOLS, frame, 8U, centre, threshold);
if (m_control == 0x40U) {
if (m_control == CONTROL_DATA) {
// Data sync
uint8_t colorCode;
uint8_t dataType;
@ -119,51 +148,107 @@ bool CDMRSlotRX::processSample(q15_t sample)
switch (dataType) {
case DT_DATA_HEADER:
DEBUG3("DMRSlotRX: data header for slot/data type", m_slot ? 2U : 1U, dataType);
m_endPtr = NOENDPTR;
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
DEBUG5("DMRSlotRX: data header found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMRRXS_DATA;
m_type = 0x00U;
break;
case DT_RATE_12_DATA:
case DT_RATE_34_DATA:
case DT_RATE_1_DATA:
if (m_state == DMRRXS_DATA) {
DEBUG5("DMRSlotRX: data payload found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_type = dataType;
}
break;
case DT_VOICE_LC_HEADER:
DEBUG3("DMRSlotRX: voice header for slot/data type", m_slot ? 2U : 1U, dataType);
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
DEBUG5("DMRSlotRX: voice header found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMRRXS_VOICE;
break;
case DT_VOICE_PI_HEADER:
DEBUG3("DMRSlotRX: pi header for slot/data type", m_slot ? 2U : 1U, dataType);
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
if (m_state == DMRRXS_VOICE) {
DEBUG5("DMRSlotRX: voice pi header found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
}
m_state = DMRRXS_VOICE;
break;
case DT_TERMINATOR_WITH_LC:
DEBUG2("DMRSlotRX: terminator for slot", m_slot ? 2U : 1U);
m_endPtr = NOENDPTR;
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
if (m_state == DMRRXS_VOICE) {
DEBUG5("DMRSlotRX: voice terminator found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMRRXS_NONE;
m_endPtr = NOENDPTR;
}
break;
default:
DEBUG3("DMRSlotRX: data sync for slot/data type", m_slot ? 2U : 1U, dataType);
default: // DT_CSBK
DEBUG5("DMRSlotRX: csbk found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMRRXS_NONE;
m_endPtr = NOENDPTR;
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
break;
}
}
} else if (m_control == 0x20U) {
} else if (m_control == CONTROL_VOICE) {
// Voice sync
DEBUG2("DMRSlotRX: voice sync for slot", m_slot ? 2U : 1U);
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
DEBUG5("DMRSlotRX: voice sync found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_syncPtr, centre, threshold);
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
m_state = DMRRXS_VOICE;
m_syncCount = 0U;
m_n = 0U;
} else {
m_syncCount++;
if (m_syncCount >= MAX_SYNC_LOST_FRAMES) {
DEBUG2("DMRSlotRX: lost for slot", m_slot ? 2U : 1U);
serial.writeDMRLost(m_slot);
m_syncCount = 0U;
m_threshold = 0;
m_centre = 0;
m_endPtr = NOENDPTR;
return false;
if (m_state != DMRRXS_NONE) {
m_syncCount++;
if (m_syncCount >= MAX_SYNC_LOST_FRAMES) {
serial.writeDMRLost(m_slot);
m_state = DMRRXS_NONE;
m_endPtr = NOENDPTR;
}
}
// Voice data
frame[0U] |= ++m_n;
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
if (m_state == DMRRXS_VOICE) {
if (m_n >= 5U) {
frame[0U] = CONTROL_VOICE;
m_n = 0U;
} else {
frame[0U] = ++m_n;
}
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
} else if (m_state == DMRRXS_DATA) {
if (m_type != 0x00U) {
frame[0U] = CONTROL_DATA | m_type;
writeRSSIData(frame);
#if defined(DUMP_SAMPLES)
writeSamples(ptr, frame[0U]);
#endif
}
}
}
}
@ -173,10 +258,10 @@ bool CDMRSlotRX::processSample(q15_t sample)
if (m_bitPtr >= DMR_RADIO_SYMBOL_LENGTH)
m_bitPtr = 0U;
return m_endPtr != NOENDPTR;
return m_state != DMRRXS_NONE;
}
void CDMRSlotRX::correlateSync(q15_t sample)
void CDMRSlotRX::correlateSync(bool first)
{
uint8_t errs = countBits32((m_bitBuffer[m_bitPtr] & DMR_SYNC_SYMBOLS_MASK) ^ DMR_MS_DATA_SYNC_SYMBOLS);
@ -191,19 +276,34 @@ void CDMRSlotRX::correlateSync(q15_t sample)
q15_t min = 16000;
q15_t max = -16000;
uint32_t mask = 0x00800000U;
for (uint8_t i = 0U; i < DMR_SYNC_LENGTH_SYMBOLS; i++, mask >>= 1) {
bool b = (DMR_MS_DATA_SYNC_SYMBOLS & mask) == mask;
for (uint8_t i = 0U; i < DMR_SYNC_LENGTH_SYMBOLS; i++) {
q15_t val = m_buffer[ptr];
if (m_buffer[ptr] > max)
max = m_buffer[ptr];
if (m_buffer[ptr] < min)
min = m_buffer[ptr];
if (val > max)
max = val;
if (val < min)
min = val;
int8_t corrVal;
if (data)
corr += b ? -m_buffer[ptr] : m_buffer[ptr];
else // if (voice)
corr += b ? m_buffer[ptr] : -m_buffer[ptr];
corrVal = DMR_MS_DATA_SYNC_SYMBOLS_VALUES[i];
else
corrVal = DMR_MS_VOICE_SYNC_SYMBOLS_VALUES[i];
switch (corrVal) {
case +3:
corr -= (val + val + val);
break;
case +1:
corr -= val;
break;
case -1:
corr += val;
break;
default: // -3
corr += (val + val + val);
break;
}
ptr += DMR_RADIO_SYMBOL_LENGTH;
}
@ -224,13 +324,24 @@ void CDMRSlotRX::correlateSync(q15_t sample)
errs += countBits8((sync[i] & DMR_SYNC_BYTES_MASK[i]) ^ DMR_MS_DATA_SYNC_BYTES[i]);
if (errs <= MAX_SYNC_BYTES_ERRS) {
DEBUG5("DMRSlotRX: data sync found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_dataPtr, centre, threshold);
m_maxCorr = corr;
m_centre = centre;
m_threshold = threshold;
m_control = 0x40U;
m_syncPtr = m_dataPtr;
m_endPtr = m_dataPtr + DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U + DMR_INFO_LENGTH_SAMPLES / 2U - 1U;
if (first) {
m_threshold[0U] = m_threshold[1U] = m_threshold[2U] = m_threshold[3U] = threshold;
m_centre[0U] = m_centre[1U] = m_centre[2U] = m_centre[3U] = centre;
m_averagePtr = 0U;
} else {
m_threshold[m_averagePtr] = threshold;
m_centre[m_averagePtr] = centre;
m_averagePtr++;
if (m_averagePtr >= 4U)
m_averagePtr = 0U;
}
m_maxCorr = corr;
m_control = CONTROL_DATA;
m_syncPtr = m_dataPtr;
m_startPtr = m_dataPtr - DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U - DMR_INFO_LENGTH_SAMPLES / 2U - DMR_SYNC_LENGTH_SAMPLES;
m_endPtr = m_dataPtr + DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U + DMR_INFO_LENGTH_SAMPLES / 2U - 1U;
}
} else { // if (voice)
uint8_t errs = 0U;
@ -238,13 +349,24 @@ void CDMRSlotRX::correlateSync(q15_t sample)
errs += countBits8((sync[i] & DMR_SYNC_BYTES_MASK[i]) ^ DMR_MS_VOICE_SYNC_BYTES[i]);
if (errs <= MAX_SYNC_BYTES_ERRS) {
DEBUG5("DMRSlotRX: voice sync found slot/pos/centre/threshold", m_slot ? 2U : 1U, m_dataPtr, centre, threshold);
m_maxCorr = corr;
m_centre = centre;
m_threshold = threshold;
m_control = 0x20U;
m_syncPtr = m_dataPtr;
m_endPtr = m_dataPtr + DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U + DMR_INFO_LENGTH_SAMPLES / 2U - 1U;
if (first) {
m_threshold[0U] = m_threshold[1U] = m_threshold[2U] = m_threshold[3U] = threshold;
m_centre[0U] = m_centre[1U] = m_centre[2U] = m_centre[3U] = centre;
m_averagePtr = 0U;
} else {
m_threshold[m_averagePtr] = threshold;
m_centre[m_averagePtr] = centre;
m_averagePtr++;
if (m_averagePtr >= 4U)
m_averagePtr = 0U;
}
m_maxCorr = corr;
m_control = CONTROL_VOICE;
m_syncPtr = m_dataPtr;
m_startPtr = m_dataPtr - DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U - DMR_INFO_LENGTH_SAMPLES / 2U - DMR_SYNC_LENGTH_SAMPLES;
m_endPtr = m_dataPtr + DMR_SLOT_TYPE_LENGTH_SAMPLES / 2U + DMR_INFO_LENGTH_SAMPLES / 2U - 1U;
}
}
}
@ -285,3 +407,41 @@ void CDMRSlotRX::setColorCode(uint8_t colorCode)
m_colorCode = colorCode;
}
void CDMRSlotRX::setDelay(uint8_t delay)
{
m_delay = delay;
}
void CDMRSlotRX::writeRSSIData(uint8_t* frame)
{
#if defined(SEND_RSSI_DATA)
// Calculate RSSI average over a burst period. We don't take into account 2.5 ms at the beginning and 2.5 ms at the end
uint16_t start = m_startPtr + DMR_SYNC_LENGTH_SAMPLES / 2U;
uint32_t accum = 0U;
for (uint16_t i = 0U; i < (DMR_FRAME_LENGTH_SAMPLES - DMR_SYNC_LENGTH_SAMPLES); i++)
accum += m_rssi[start++];
uint16_t avg = accum / (DMR_FRAME_LENGTH_SAMPLES - DMR_SYNC_LENGTH_SAMPLES);
frame[34U] = (avg >> 8) & 0xFFU;
frame[35U] = (avg >> 0) & 0xFFU;
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 3U);
#else
serial.writeDMRData(m_slot, frame, DMR_FRAME_LENGTH_BYTES + 1U);
#endif
}
#if defined(DUMP_SAMPLES)
void CDMRSlotRX::writeSamples(uint16_t start, uint8_t control)
{
q15_t samples[DMR_FRAME_LENGTH_SYMBOLS];
for (uint16_t i = 0U; i < DMR_FRAME_LENGTH_SYMBOLS; i++) {
samples[i] = m_buffer[start];
start += DMR_RADIO_SYMBOL_LENGTH;
}
serial.writeSamples(STATE_DMR, control, samples, DMR_FRAME_LENGTH_SYMBOLS);
}
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -22,37 +22,52 @@
#include "Config.h"
#include "DMRDefines.h"
enum DMRRX_STATE {
DMRRXS_NONE,
DMRRXS_VOICE,
DMRRXS_DATA
};
class CDMRSlotRX {
public:
CDMRSlotRX(bool slot);
void start();
bool processSample(q15_t sample);
bool processSample(q15_t sample, uint16_t rssi);
void setColorCode(uint8_t colorCode);
void setDelay(uint8_t delay);
void reset();
private:
bool m_slot;
uint32_t m_bitBuffer[DMR_RADIO_SYMBOL_LENGTH];
q15_t m_buffer[900U];
uint16_t m_bitPtr;
uint16_t m_dataPtr;
uint16_t m_syncPtr;
uint16_t m_endPtr;
q31_t m_maxCorr;
q15_t m_centre;
q15_t m_threshold;
uint8_t m_control;
uint8_t m_syncCount;
uint8_t m_colorCode;
uint8_t m_n;
bool m_slot;
uint32_t m_bitBuffer[DMR_RADIO_SYMBOL_LENGTH];
q15_t m_buffer[900U];
uint16_t m_bitPtr;
uint16_t m_dataPtr;
uint16_t m_syncPtr;
uint16_t m_startPtr;
uint16_t m_endPtr;
uint16_t m_delayPtr;
q31_t m_maxCorr;
q15_t m_centre[4U];
q15_t m_threshold[4U];
uint8_t m_averagePtr;
uint8_t m_control;
uint8_t m_syncCount;
uint8_t m_colorCode;
uint16_t m_delay;
DMRRX_STATE m_state;
uint8_t m_n;
uint8_t m_type;
uint16_t m_rssi[900U];
void correlateSync(q15_t sample);
void samplesToBits(uint16_t start, uint8_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void correlateSync(bool first);
void samplesToBits(uint16_t start, uint8_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void writeRSSIData(uint8_t* frame);
void writeSamples(uint16_t start, uint8_t control);
};
#endif

159
DMRTX.cpp
View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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
@ -16,20 +17,29 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "DMRSlotType.h"
#if defined(WIDE_C4FSK_FILTERS_TX)
// Generated using rcosdesign(0.2, 4, 5, 'sqrt') in MATLAB
static q15_t DMR_C4FSK_FILTER[] = {688, -680, -2158, -3060, -2724, -775, 2684, 7041, 11310, 14425, 15565, 14425,
11310, 7041, 2684, -775, -2724, -3060, -2158, -680, 688, 0};
const uint16_t DMR_C4FSK_FILTER_LEN = 22U;
#else
// Generated using rcosdesign(0.2, 8, 5, 'sqrt') in MATLAB
static q15_t DMR_C4FSK_FILTER[] = {401, 104, -340, -731, -847, -553, 112, 909, 1472, 1450, 683, -675, -2144, -3040, -2706, -770, 2667, 6995,
11237, 14331, 15464, 14331, 11237, 6995, 2667, -770, -2706, -3040, -2144, -675, 683, 1450, 1472, 909, 112,
-553, -847, -731, -340, 104, 401, 0};
const uint16_t DMR_C4FSK_FILTER_LEN = 42U;
#endif
q15_t DMR_A[] = { 1280, 1280, 1280, 1280, 1280};
q15_t DMR_B[] = { 427, 427, 427, 427, 427};
q15_t DMR_C[] = { -427, -427, -427, -427, -427};
q15_t DMR_D[] = {-1280, -1280, -1280, -1280, -1280};
const q15_t DMR_LEVELA[] = { 640, 640 , 640, 640, 640};
const q15_t DMR_LEVELB[] = { 213, 213, 213, 213, 213};
const q15_t DMR_LEVELC[] = {-213, -213, -213, -213, -213};
const q15_t DMR_LEVELD[] = {-640, -640, -640, -640, -640};
// The PR FILL and Data Sync pattern.
const uint8_t IDLE_DATA[] =
@ -44,7 +54,7 @@ const uint8_t CACH_INTERLEAVE[] =
73U, 74U, 75U, 77U, 78U, 79U, 81U, 82U, 83U, 85U, 87U, 88U, 89U, 91U, 92U, 93U, 95U};
const uint8_t EMPTY_SHORT_LC[] =
{0x00U, 0x08U, 0x44U, 0x00U, 0x88U, 0x18U, 0x63U, 0x89U, 0x18U, 0x64U, 0x80U, 0x00U};
{0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U, 0x00U};
const uint8_t BIT_MASK_TABLE[] = {0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02U, 0x01U};
@ -63,7 +73,9 @@ m_newShortLC(),
m_markBuffer(),
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U)
m_poPtr(0U),
m_count(0U),
m_abort()
{
::memset(m_modState, 0x00U, 70U * sizeof(q15_t));
@ -73,6 +85,9 @@ m_poPtr(0U)
::memcpy(m_newShortLC, EMPTY_SHORT_LC, 12U);
::memcpy(m_shortLC, EMPTY_SHORT_LC, 12U);
m_abort[0U] = false;
m_abort[1U] = false;
}
void CDMRTX::process()
@ -97,6 +112,10 @@ void CDMRTX::process()
m_state = DMRTXSTATE_CACH1;
break;
case DMRTXSTATE_CAL:
createCal();
break;
default:
createCACH(0U, 1U);
m_state = DMRTXSTATE_SLOT1;
@ -107,7 +126,7 @@ void CDMRTX::process()
if (m_poLen > 0U) {
uint16_t space = io.getSpace();
while (space > (4U * DMR_RADIO_SYMBOL_LENGTH) && space < 1000U) {
while (space > (4U * DMR_RADIO_SYMBOL_LENGTH)) {
uint8_t c = m_poBuffer[m_poPtr];
uint8_t m = m_markBuffer[m_poPtr];
m_poPtr++;
@ -134,6 +153,11 @@ uint8_t CDMRTX::writeData1(const uint8_t* data, uint8_t length)
if (space < DMR_FRAME_LENGTH_BYTES)
return 5U;
if (m_abort[0U]) {
m_fifo[0U].reset();
m_abort[0U] = false;
}
for (uint8_t i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++)
m_fifo[0U].put(data[i + 1U]);
@ -153,6 +177,11 @@ uint8_t CDMRTX::writeData2(const uint8_t* data, uint8_t length)
if (space < DMR_FRAME_LENGTH_BYTES)
return 5U;
if (m_abort[1U]) {
m_fifo[1U].reset();
m_abort[1U] = false;
}
for (uint8_t i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++)
m_fifo[1U].put(data[i + 1U]);
@ -176,24 +205,49 @@ uint8_t CDMRTX::writeShortLC(const uint8_t* data, uint8_t length)
WRITE_BIT1(m_newShortLC, n, b);
}
// Set the LCSS bits
m_newShortLC[1U] |= 0x08U;
m_newShortLC[4U] |= 0x88U;
m_newShortLC[7U] |= 0x88U;
m_newShortLC[10U] |= 0x80U;
return 0U;
}
uint8_t CDMRTX::writeAbort(const uint8_t* data, uint8_t length)
{
if (length != 1U)
return 4U;
switch (data[0U]) {
case 1U:
m_abort[0U] = true;
return 0U;
case 2U:
m_abort[1U] = true;
return 0U;
default:
return 4U;
}
}
void CDMRTX::setStart(bool start)
{
m_state = start ? DMRTXSTATE_SLOT1 : DMRTXSTATE_IDLE;
m_count = 0U;
m_abort[0U] = false;
m_abort[1U] = false;
}
void CDMRTX::setCal(bool start)
{
m_state = start ? DMRTXSTATE_CAL : DMRTXSTATE_IDLE;
m_count = 0U;
}
void CDMRTX::writeByte(uint8_t c, uint8_t control)
{
q15_t inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U];
q15_t outBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U];
q15_t inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U + 1U];
q15_t outBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U + 1U];
const uint8_t MASK = 0xC0U;
@ -201,27 +255,50 @@ void CDMRTX::writeByte(uint8_t c, uint8_t control)
for (uint8_t i = 0U; i < 4U; i++, c <<= 2, p += DMR_RADIO_SYMBOL_LENGTH) {
switch (c & MASK) {
case 0xC0U:
::memcpy(p, DMR_A, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, DMR_LEVELA, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x80U:
::memcpy(p, DMR_B, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, DMR_LEVELB, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x00U:
::memcpy(p, DMR_C, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, DMR_LEVELC, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
default:
::memcpy(p, DMR_D, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, DMR_LEVELD, DMR_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
}
}
uint8_t controlBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U];
uint16_t blockSize = DMR_RADIO_SYMBOL_LENGTH * 4U;
uint8_t controlBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U + 1U];
::memset(controlBuffer, MARK_NONE, DMR_RADIO_SYMBOL_LENGTH * 4U * sizeof(uint8_t));
controlBuffer[DMR_RADIO_SYMBOL_LENGTH * 2U] = control;
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, DMR_RADIO_SYMBOL_LENGTH * 4U);
// Handle the case of the oscillator not being accurate enough
if (m_sampleCount > 0U) {
m_count += DMR_RADIO_SYMBOL_LENGTH * 4U;
io.write(outBuffer, DMR_RADIO_SYMBOL_LENGTH * 4U, controlBuffer);
if (m_count >= m_sampleCount) {
if (m_sampleInsert) {
inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U] = inBuffer[DMR_RADIO_SYMBOL_LENGTH * 4U - 1U];
for (int8_t i = DMR_RADIO_SYMBOL_LENGTH * 4U - 1; i >= 0; i--)
controlBuffer[i + 1] = controlBuffer[i];
blockSize++;
} else {
controlBuffer[DMR_RADIO_SYMBOL_LENGTH * 2U - 1U] = control;
for (uint8_t i = 0U; i < (DMR_RADIO_SYMBOL_LENGTH * 4U - 1U); i++)
controlBuffer[i] = controlBuffer[i + 1U];
blockSize--;
}
m_count -= m_sampleCount;
}
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, blockSize);
io.write(STATE_DMR, outBuffer, blockSize, controlBuffer);
}
uint16_t CDMRTX::getSpace1() const
@ -242,6 +319,7 @@ void CDMRTX::createData(uint8_t slotIndex)
m_markBuffer[i] = MARK_NONE;
}
} else {
m_abort[slotIndex] = false;
// Transmit an idle message
for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++) {
m_poBuffer[i] = m_idle[i];
@ -253,6 +331,17 @@ void CDMRTX::createData(uint8_t slotIndex)
m_poPtr = 0U;
}
void CDMRTX::createCal()
{
for (unsigned int i = 0U; i < DMR_FRAME_LENGTH_BYTES; i++) {
m_poBuffer[i] = 0x5FU; // +3, +3, -3, -3 pattern for deviation cal.
m_markBuffer[i] = MARK_NONE;
}
m_poLen = DMR_FRAME_LENGTH_BYTES;
m_poPtr = 0U;
}
void CDMRTX::createCACH(uint8_t txSlotIndex, uint8_t rxSlotIndex)
{
if (m_cachPtr >= 12U)
@ -272,23 +361,25 @@ void CDMRTX::createCACH(uint8_t txSlotIndex, uint8_t rxSlotIndex)
bool at = m_fifo[rxSlotIndex].getData() > 0U;
bool tc = txSlotIndex == 1U;
bool lcss0 = true; // For 1 and 2
bool lcss1 = true;
bool ls0 = true; // For 1 and 2
bool ls1 = true;
if (m_cachPtr == 0U) // For 0
lcss0 = false;
ls1 = false;
else if (m_cachPtr == 9U) // For 3
lcss1 = false;
ls0 = false;
bool h0 = at ^ tc ^ lcss0;
bool h1 = tc ^ lcss0 ^ lcss1;
bool h2 = at ^ tc ^ lcss1;
bool h0 = at ^ tc ^ ls1;
bool h1 = tc ^ ls1 ^ ls0;
bool h2 = at ^ tc ^ ls0;
m_poBuffer[0U] |= at ? 0x80U : 0x00U;
m_poBuffer[0U] |= tc ? 0x08U : 0x00U;
m_poBuffer[1U] |= h0 ? 0x02U : 0x00U;
m_poBuffer[2U] |= h1 ? 0x20U : 0x00U;
m_poBuffer[2U] |= h2 ? 0x02U : 0x00U;
m_poBuffer[0U] |= at ? 0x80U : 0x00U;
m_poBuffer[0U] |= tc ? 0x08U : 0x00U;
m_poBuffer[1U] |= ls1 ? 0x80U : 0x00U;
m_poBuffer[1U] |= ls0 ? 0x08U : 0x00U;
m_poBuffer[1U] |= h0 ? 0x02U : 0x00U;
m_poBuffer[2U] |= h1 ? 0x20U : 0x00U;
m_poBuffer[2U] |= h2 ? 0x02U : 0x00U;
m_poLen = DMR_CACH_LENGTH_BYTES;
m_poPtr = 0U;

12
DMRTX.h
View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -29,7 +30,8 @@ enum DMRTXSTATE {
DMRTXSTATE_SLOT1,
DMRTXSTATE_CACH1,
DMRTXSTATE_SLOT2,
DMRTXSTATE_CACH2
DMRTXSTATE_CACH2,
DMRTXSTATE_CAL
};
class CDMRTX {
@ -38,9 +40,12 @@ public:
uint8_t writeData1(const uint8_t* data, uint8_t length);
uint8_t writeData2(const uint8_t* data, uint8_t length);
uint8_t writeShortLC(const uint8_t* data, uint8_t length);
uint8_t writeAbort(const uint8_t* data, uint8_t length);
void setStart(bool start);
void setCal(bool start);
void process();
@ -62,9 +67,12 @@ private:
uint8_t m_poBuffer[40U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint32_t m_count;
bool m_abort[2U];
void createData(uint8_t slotIndex);
void createCACH(uint8_t txSlotIndex, uint8_t rxSlotIndex);
void createCal();
void writeByte(uint8_t c, uint8_t control);
};

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,6 +16,8 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "DStarRX.h"
@ -29,6 +31,10 @@ const uint32_t INC = PLLINC / 32U;
const unsigned int MAX_SYNC_BITS = 50U * DSTAR_DATA_LENGTH_BITS;
const unsigned int SYNC_POS = 21U * DSTAR_DATA_LENGTH_BITS;
const unsigned int SYNC_SCAN_START = SYNC_POS - 3U;
const unsigned int SYNC_SCAN_END = SYNC_POS + 3U;
const q15_t THRESHOLD = 0;
// D-Star bit order version of 0x55 0x55 0x6E 0x0A
@ -253,8 +259,8 @@ m_pathMemory1(),
m_pathMemory2(),
m_pathMemory3(),
m_fecOutput(),
m_samples(),
m_samplesPtr(0U)
m_rssiAccum(0U),
m_rssiCount(0U)
{
}
@ -266,13 +272,15 @@ void CDStarRX::reset()
m_patternBuffer = 0x00U;
m_rxBufferBits = 0U;
m_dataBits = 0U;
m_samplesPtr = 0U;
m_rssiAccum = 0U;
m_rssiCount = 0U;
}
void CDStarRX::samples(const q15_t* samples, uint8_t length)
void CDStarRX::samples(const q15_t* samples, const uint16_t* rssi, uint8_t length)
{
for (uint16_t i = 0U; i < length; i++) {
m_samples[m_samplesPtr] = samples[i];
m_rssiAccum += rssi[i];
m_rssiCount++;
bool bit = samples[i] < THRESHOLD;
@ -304,10 +312,6 @@ void CDStarRX::samples(const q15_t* samples, uint8_t length)
break;
}
}
m_samplesPtr++;
if (m_samplesPtr >= DSTAR_DATA_SYNC_LENGTH_BITS)
m_samplesPtr = 0U;
}
}
@ -317,13 +321,16 @@ void CDStarRX::processNone(bool bit)
if (bit)
m_patternBuffer |= 0x01U;
// Exact matching of the frame sync sequence
if (countBits32((m_patternBuffer & FRAME_SYNC_MASK) ^ FRAME_SYNC_DATA) == 0U) {
// Fuzzy matching of the frame sync sequence
if (countBits32((m_patternBuffer & FRAME_SYNC_MASK) ^ FRAME_SYNC_DATA) <= FRAME_SYNC_ERRS) {
DEBUG1("DStarRX: found frame sync in None");
::memset(m_rxBuffer, 0x00U, DSTAR_FEC_SECTION_LENGTH_BYTES);
m_rxBufferBits = 0U;
m_rssiAccum = 0U;
m_rssiCount = 0U;
m_rxState = DSRXS_HEADER;
return;
}
@ -331,27 +338,22 @@ void CDStarRX::processNone(bool bit)
// Exact matching of the data sync bit sequence
if (countBits32((m_patternBuffer & DATA_SYNC_MASK) ^ DATA_SYNC_DATA) == 0U) {
DEBUG1("DStarRX: found data sync in None");
io.setDecode(true);
io.setADCDetection(true);
#if defined(WANT_DEBUG)
q15_t min = 16000;
q15_t max = -16000;
for (uint8_t i = 0U; i < DSTAR_DATA_SYNC_LENGTH_BITS; i++) {
if (m_samples[i] > max)
max = m_samples[i];
if (m_samples[i] < min)
min = m_samples[i];
}
DEBUG3("DStarRX: data sync found min/max", min, max);
#endif
// Suppress RSSI on the dummy sync message
m_rssiAccum = 0U;
m_rssiCount = 0U;
serial.writeDStarData(DSTAR_DATA_SYNC_BYTES, DSTAR_DATA_LENGTH_BYTES);
::memcpy(m_rxBuffer, DSTAR_DATA_SYNC_BYTES, DSTAR_DATA_LENGTH_BYTES);
writeRSSIData(m_rxBuffer);
::memset(m_rxBuffer, 0x00U, DSTAR_DATA_LENGTH_BYTES);
::memset(m_rxBuffer, 0x00U, DSTAR_DATA_LENGTH_BYTES + 2U);
m_rxBufferBits = 0U;
m_dataBits = MAX_SYNC_BITS;
m_rxState = DSRXS_DATA;
m_dataBits = 0U;
m_rxState = DSRXS_DATA;
return;
}
}
@ -371,19 +373,17 @@ void CDStarRX::processHeader(bool bit)
unsigned char header[DSTAR_HEADER_LENGTH_BYTES];
bool ok = rxHeader(m_rxBuffer, header);
if (ok) {
DEBUG1("DStarRX: header checksum ok");
io.setDecode(true);
io.setADCDetection(true);
serial.writeDStarHeader(header, DSTAR_HEADER_LENGTH_BYTES);
writeRSSIHeader(header);
::memset(m_rxBuffer, 0x00U, DSTAR_DATA_LENGTH_BYTES);
::memset(m_rxBuffer, 0x00U, DSTAR_DATA_LENGTH_BYTES + 2U);
m_rxBufferBits = 0U;
m_rxState = DSRXS_DATA;
m_dataBits = MAX_SYNC_BITS;
m_rxState = DSRXS_DATA;
m_dataBits = SYNC_POS - DSTAR_DATA_LENGTH_BITS + 1U;
} else {
DEBUG1("DStarRX: header checksum failed");
// The checksum failed, return to looking for syncs
m_rxState = DSRXS_NONE;
}
@ -402,7 +402,9 @@ void CDStarRX::processData(bool bit)
// Fuzzy matching of the end frame sequences
if (countBits32((m_patternBuffer & END_SYNC_MASK) ^ END_SYNC_DATA) <= END_SYNC_ERRS) {
DEBUG1("DStarRX: Found end sync in Data");
io.setDecode(false);
io.setADCDetection(false);
serial.writeDStarEOT();
@ -412,72 +414,108 @@ void CDStarRX::processData(bool bit)
// Fuzzy matching of the data sync bit sequence
bool syncSeen = false;
if (m_rxBufferBits >= (DSTAR_DATA_LENGTH_BITS - 3U)) {
if (m_dataBits >= SYNC_SCAN_START && m_dataBits <= (SYNC_POS + 1U)) {
if (countBits32((m_patternBuffer & DATA_SYNC_MASK) ^ DATA_SYNC_DATA) <= DATA_SYNC_ERRS) {
#if defined(WANT_DEBUG)
if (m_rxBufferBits < DSTAR_DATA_LENGTH_BITS)
DEBUG2("DStarRX: found data sync in Data, early", DSTAR_DATA_LENGTH_BITS - m_rxBufferBits);
if (m_dataBits < SYNC_POS)
DEBUG2("DStarRX: found data sync in Data, early", SYNC_POS - m_dataBits);
else
DEBUG1("DStarRX: found data sync in Data");
q15_t min = 16000;
q15_t max = -16000;
for (uint8_t i = 0U; i < DSTAR_DATA_SYNC_LENGTH_BITS; i++) {
if (m_samples[i] > max)
max = m_samples[i];
if (m_samples[i] < min)
min = m_samples[i];
}
DEBUG3("DStarRX: data sync found min/max", min, max);
#endif
m_rxBufferBits = DSTAR_DATA_LENGTH_BITS;
m_dataBits = MAX_SYNC_BITS;
syncSeen = true;
m_dataBits = 0U;
syncSeen = true;
}
}
// We've not seen a data sync for too long, signal RXLOST and change to RX_NONE
m_dataBits--;
if (m_dataBits == 0U) {
DEBUG1("DStarRX: data sync timed out, lost lock");
io.setDecode(false);
serial.writeDStarLost();
m_rxState = DSRXS_NONE;
return;
}
// Check to see if the sync is arriving late
if (m_rxBufferBits == DSTAR_DATA_LENGTH_BITS && !syncSeen) {
if (m_dataBits == SYNC_POS) {
for (uint8_t i = 1U; i <= 3U; i++) {
uint32_t syncMask = DATA_SYNC_MASK >> i;
uint32_t syncData = DATA_SYNC_DATA >> i;
if (countBits32((m_patternBuffer & syncMask) ^ syncData) <= DATA_SYNC_ERRS) {
DEBUG2("DStarRX: found data sync in Data, late", i);
m_rxBufferBits -= i;
m_dataBits -= i;
break;
}
}
}
m_dataBits++;
// We've not seen a data sync for too long, signal RXLOST and change to RX_NONE
if (m_dataBits >= MAX_SYNC_BITS) {
DEBUG1("DStarRX: data sync timed out, lost lock");
io.setDecode(false);
io.setADCDetection(false);
serial.writeDStarLost();
m_rxState = DSRXS_NONE;
return;
}
// Send a data frame to the host if the required number of bits have been received, or if a data sync has been seen
if (m_rxBufferBits == DSTAR_DATA_LENGTH_BITS) {
if (syncSeen) {
m_rxBuffer[9U] = DSTAR_DATA_SYNC_BYTES[9U];
m_rxBuffer[10U] = DSTAR_DATA_SYNC_BYTES[10U];
m_rxBuffer[11U] = DSTAR_DATA_SYNC_BYTES[11U];
}
serial.writeDStarData(m_rxBuffer, DSTAR_DATA_LENGTH_BYTES);
writeRSSIData(m_rxBuffer);
} else {
serial.writeDStarData(m_rxBuffer, DSTAR_DATA_LENGTH_BYTES);
}
// Start the next frame
::memset(m_rxBuffer, 0x00U, DSTAR_DATA_LENGTH_BYTES);
::memset(m_rxBuffer, 0x00U, DSTAR_DATA_LENGTH_BYTES + 2U);
m_rxBufferBits = 0U;
}
}
void CDStarRX::writeRSSIHeader(unsigned char* header)
{
#if defined(SEND_RSSI_DATA)
if (m_rssiCount > 0U) {
uint16_t rssi = m_rssiAccum / m_rssiCount;
header[41U] = (rssi >> 8) & 0xFFU;
header[42U] = (rssi >> 0) & 0xFFU;
serial.writeDStarHeader(header, DSTAR_HEADER_LENGTH_BYTES + 2U);
} else {
serial.writeDStarHeader(header, DSTAR_HEADER_LENGTH_BYTES + 0U);
}
#else
serial.writeDStarHeader(header, DSTAR_HEADER_LENGTH_BYTES + 0U);
#endif
m_rssiAccum = 0U;
m_rssiCount = 0U;
}
void CDStarRX::writeRSSIData(unsigned char* data)
{
#if defined(SEND_RSSI_DATA)
if (m_rssiCount > 0U) {
uint16_t rssi = m_rssiAccum / m_rssiCount;
data[12U] = (rssi >> 8) & 0xFFU;
data[13U] = (rssi >> 0) & 0xFFU;
serial.writeDStarData(data, DSTAR_DATA_LENGTH_BYTES + 2U);
} else {
serial.writeDStarData(data, DSTAR_DATA_LENGTH_BYTES + 0U);
}
#else
serial.writeDStarData(data, DSTAR_DATA_LENGTH_BYTES + 0U);
#endif
m_rssiAccum = 0U;
m_rssiCount = 0U;
}
bool CDStarRX::rxHeader(uint8_t* in, uint8_t* out)
{
int i;
@ -693,4 +731,3 @@ bool CDStarRX::checksum(const uint8_t* header) const
return crc8[0U] == header[DSTAR_HEADER_LENGTH_BYTES - 2U] && crc8[1U] == header[DSTAR_HEADER_LENGTH_BYTES - 1U];
}

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -32,7 +32,7 @@ class CDStarRX {
public:
CDStarRX();
void samples(const q15_t* samples, uint8_t length);
void samples(const q15_t* samples, const uint16_t* rssi, uint8_t length);
void reset();
@ -51,12 +51,14 @@ private:
unsigned int m_pathMemory2[42U];
unsigned int m_pathMemory3[42U];
uint8_t m_fecOutput[42U];
q15_t m_samples[DSTAR_DATA_SYNC_LENGTH_BITS];
uint8_t m_samplesPtr;
uint32_t m_rssiAccum;
uint16_t m_rssiCount;
void processNone(bool bit);
void processHeader(bool bit);
void processData(bool bit);
void writeRSSIHeader(unsigned char* header);
void writeRSSIData(unsigned char* data);
bool rxHeader(uint8_t* in, uint8_t* out);
void acs(int* metric);
void viterbiDecode(int* data);

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,6 +16,8 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "DStarTX.h"
@ -30,8 +32,8 @@ const uint8_t FRAME_SYNC[] = {0xEAU, 0xA6U, 0x00U};
static q15_t DSTAR_GMSK_FILTER[] = {8, 104, 760, 3158, 7421, 9866, 7421, 3158, 760, 104, 8, 0};
const uint16_t DSTAR_GMSK_FILTER_LEN = 12U;
q15_t DSTAR_1[] = { 1600, 1600, 1600, 1600, 1600};
q15_t DSTAR_0[] = {-1600, -1600, -1600, -1600, -1600};
const q15_t DSTAR_LEVEL0[] = {-800, -800, -800, -800, -800};
const q15_t DSTAR_LEVEL1[] = { 800, 800, 800, 800, 800};
const uint8_t BIT_MASK_TABLE[] = {0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02U, 0x01U};
@ -193,7 +195,8 @@ m_modState(),
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U),
m_txDelay(60U) // 100ms
m_txDelay(60U), // 100ms
m_count(0U)
{
::memset(m_modState, 0x00U, 60U * sizeof(q15_t));
@ -211,6 +214,8 @@ void CDStarTX::process()
if (type == DSTAR_HEADER && m_poLen == 0U) {
if (!m_tx) {
m_count = 0U;
for (uint16_t i = 0U; i < m_txDelay; i++)
m_poBuffer[m_poLen++] = BIT_SYNC;
} else {
@ -236,6 +241,9 @@ void CDStarTX::process()
}
if (type == DSTAR_DATA && m_poLen == 0U) {
if (!m_tx)
m_count = 0U;
// Pop the type byte off
m_buffer.get();
@ -260,7 +268,7 @@ void CDStarTX::process()
if (m_poLen > 0U) {
uint16_t space = io.getSpace();
while (space > (8U * DSTAR_RADIO_BIT_LENGTH) && space < 1000U) {
while (space > (8U * DSTAR_RADIO_BIT_LENGTH)) {
uint8_t c = m_poBuffer[m_poPtr++];
writeByte(c);
@ -281,8 +289,10 @@ uint8_t CDStarTX::writeHeader(const uint8_t* header, uint8_t length)
return 4U;
uint16_t space = m_buffer.getSpace();
if (space < (DSTAR_HEADER_LENGTH_BYTES + 1U))
if (space < (DSTAR_HEADER_LENGTH_BYTES + 1U)) {
DEBUG2("DStarTX: header space available", space);
return 5U;
}
m_buffer.put(DSTAR_HEADER);
@ -298,8 +308,10 @@ uint8_t CDStarTX::writeData(const uint8_t* data, uint8_t length)
return 4U;
uint16_t space = m_buffer.getSpace();
if (space < (DSTAR_DATA_LENGTH_BYTES + 1U))
if (space < (DSTAR_DATA_LENGTH_BYTES + 1U)) {
DEBUG2("DStarTX: data space available", space);
return 5U;
}
m_buffer.put(DSTAR_DATA);
@ -312,8 +324,10 @@ uint8_t CDStarTX::writeData(const uint8_t* data, uint8_t length)
uint8_t CDStarTX::writeEOT()
{
uint16_t space = m_buffer.getSpace();
if (space < 1U)
if (space < 1U) {
DEBUG2("DStarTX: EOT space available", space);
return 5U;
}
m_buffer.put(DSTAR_EOT);
@ -403,29 +417,47 @@ void CDStarTX::txHeader(const uint8_t* in, uint8_t* out) const
void CDStarTX::writeByte(uint8_t c)
{
q15_t inBuffer[DSTAR_RADIO_BIT_LENGTH * 8U];
q15_t outBuffer[DSTAR_RADIO_BIT_LENGTH * 8U];
q15_t inBuffer[DSTAR_RADIO_BIT_LENGTH * 8U + 1U];
q15_t outBuffer[DSTAR_RADIO_BIT_LENGTH * 8U + 1U];
uint8_t mask = 0x01U;
q15_t* p = inBuffer;
for (uint8_t i = 0U; i < 8U; i++, p += DSTAR_RADIO_BIT_LENGTH) {
if ((c & mask) == mask)
::memcpy(p, DSTAR_0, DSTAR_RADIO_BIT_LENGTH * sizeof(q15_t));
::memcpy(p, DSTAR_LEVEL0, DSTAR_RADIO_BIT_LENGTH * sizeof(q15_t));
else
::memcpy(p, DSTAR_1, DSTAR_RADIO_BIT_LENGTH * sizeof(q15_t));
::memcpy(p, DSTAR_LEVEL1, DSTAR_RADIO_BIT_LENGTH * sizeof(q15_t));
mask <<= 1;
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, DSTAR_RADIO_BIT_LENGTH * 8U);
uint16_t blockSize = DSTAR_RADIO_BIT_LENGTH * 8U;
io.write(outBuffer, DSTAR_RADIO_BIT_LENGTH * 8U);
// Handle the case of the oscillator not being accurate enough
if (m_sampleCount > 0U) {
m_count += DSTAR_RADIO_BIT_LENGTH * 8U;
if (m_count >= m_sampleCount) {
if (m_sampleInsert) {
inBuffer[DSTAR_RADIO_BIT_LENGTH * 8U] = inBuffer[DSTAR_RADIO_BIT_LENGTH * 8U - 1U];
blockSize++;
} else {
blockSize--;
}
m_count -= m_sampleCount;
}
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, blockSize);
io.write(STATE_DSTAR, outBuffer, blockSize);
}
void CDStarTX::setTXDelay(uint8_t delay)
{
m_txDelay = 60U + uint16_t(delay) * 6U; // 100ms + tx delay
m_txDelay = 300U + uint16_t(delay) * 6U; // 250ms + tx delay
}
uint16_t CDStarTX::getSpace() const

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -41,10 +41,11 @@ private:
CSerialRB m_buffer;
arm_fir_instance_q15 m_modFilter;
q15_t m_modState[60U]; // NoTaps + BlockSize - 1, 12 + 40 - 1 plus some spare
uint8_t m_poBuffer[400U];
uint8_t m_poBuffer[600U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint16_t m_txDelay; // In bytes
uint32_t m_count;
void txHeader(const uint8_t* in, uint8_t* out) const;
void writeByte(uint8_t c);

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -31,8 +31,6 @@
#define DEBUG4(a,b,c,d) serial.writeDebug((a),(b),(c),(d))
#define DEBUG5(a,b,c,d,e) serial.writeDebug((a),(b),(c),(d),(e))
#define ASSERT(a) serial.writeAssert((a),#a,__FILE__,__LINE__)
#define DUMP(a,b) serial.writeDump((a),(b))
#define SAMPLES(a,b) serial.writeSamples((a),(b))
#else
@ -42,8 +40,6 @@
#define DEBUG4(a,b,c,d)
#define DEBUG5(a,b,c,d,e)
#define ASSERT(a)
#define DUMP(a,b)
#define SAMPLES(a,b)
#endif

View File

@ -19,19 +19,20 @@
#if !defined(GLOBALS_H)
#define GLOBALS_H
#if defined(__MBED__)
#include "mbed.h"
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#else
#include <Arduino.h>
#endif
#if defined(__SAM3X8E__) || defined(__STM32F1__) || defined(__STM32F2__)
#if defined(__SAM3X8E__)
#define ARM_MATH_CM3
#elif defined(__MK20DX256__) || defined(__STM32F3__) || defined(__STM32F4__)
#elif defined(STM32F4XX) || defined(STM32F4) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
#define ARM_MATH_CM4
#else
#error "Unknown processor type"
#endif
#include <arm_math.h>
enum MMDVM_STATE {
@ -39,19 +40,32 @@ enum MMDVM_STATE {
STATE_DSTAR = 1,
STATE_DMR = 2,
STATE_YSF = 3,
STATE_CALIBRATE = 99
STATE_P25 = 4,
// Dummy states start at 90
STATE_RSSICAL = 96,
STATE_CWID = 97,
STATE_DMRCAL = 98,
STATE_DSTARCAL = 99
};
#include "SerialPort.h"
#include "DMRIdleRX.h"
#include "DMRDMORX.h"
#include "DMRDMOTX.h"
#include "DStarRX.h"
#include "DStarTX.h"
#include "DMRRX.h"
#include "DMRTX.h"
#include "YSFRX.h"
#include "YSFTX.h"
#include "CalRX.h"
#include "CalTX.h"
#include "P25RX.h"
#include "P25TX.h"
#include "CalDStarRX.h"
#include "CalDStarTX.h"
#include "CalDMR.h"
#include "CalRSSI.h"
#include "CWIdTX.h"
#include "Debug.h"
#include "IO.h"
@ -59,15 +73,25 @@ const uint8_t MARK_SLOT1 = 0x08U;
const uint8_t MARK_SLOT2 = 0x04U;
const uint8_t MARK_NONE = 0x00U;
const uint16_t RX_BLOCK_SIZE = 20U;
const uint16_t RX_BLOCK_SIZE = 2U;
const uint16_t TX_RINGBUFFER_SIZE = 500U;
const uint16_t RX_RINGBUFFER_SIZE = 600U;
extern MMDVM_STATE m_modemState;
extern bool m_dstarEnable;
extern bool m_dmrEnable;
extern bool m_ysfEnable;
extern bool m_p25Enable;
extern bool m_duplex;
extern bool m_tx;
extern bool m_dcd;
extern uint32_t m_sampleCount;
extern bool m_sampleInsert;
extern CSerialPort serial;
extern CIO io;
@ -79,11 +103,21 @@ extern CDMRIdleRX dmrIdleRX;
extern CDMRRX dmrRX;
extern CDMRTX dmrTX;
extern CDMRDMORX dmrDMORX;
extern CDMRDMOTX dmrDMOTX;
extern CYSFRX ysfRX;
extern CYSFTX ysfTX;
extern CCalRX calRX;
extern CCalTX calTX;
extern CP25RX p25RX;
extern CP25TX p25TX;
extern CCalDStarRX calDStarRX;
extern CCalDStarTX calDStarTX;
extern CCalDMR calDMR;
extern CCalRSSI calRSSI;
extern CCWIdTX cwIdTX;
#endif

432
IO.cpp
View File

@ -1,5 +1,7 @@
/*
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
* Copyright (C) 2015 by Jim Mclaughlin KI6ZUM
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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
@ -16,15 +18,24 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "IO.h"
#if defined(WIDE_C4FSK_FILTERS_RX)
// Generated using rcosdesign(0.2, 4, 5, 'sqrt') in MATLAB
static q15_t C4FSK_FILTER[] = {688, -680, -2158, -3060, -2724, -775, 2684, 7041, 11310, 14425, 15565, 14425,
11310, 7041, 2684, -775, -2724, -3060, -2158, -680, 688, 0};
const uint16_t C4FSK_FILTER_LEN = 22U;
#else
// Generated using rcosdesign(0.2, 8, 5, 'sqrt') in MATLAB
static q15_t C4FSK_FILTER[] = {401, 104, -340, -731, -847, -553, 112, 909, 1472, 1450, 683, -675, -2144, -3040, -2706, -770, 2667, 6995,
11237, 14331, 15464, 14331, 11237, 6995, 2667, -770, -2706, -3040, -2144, -675, 683, 1450, 1472, 909, 112,
-553, -847, -731, -340, 104, 401, 0};
static q15_t C4FSK_FILTER[] = {401, 104, -340, -731, -847, -553, 112, 909, 1472, 1450, 683, -675, -2144, -3040, -2706, -770, 2667, 6995,
11237, 14331, 15464, 14331, 11237, 6995, 2667, -770, -2706, -3040, -2144, -675, 683, 1450, 1472, 909, 112,
-553, -847, -731, -340, 104, 401, 0};
const uint16_t C4FSK_FILTER_LEN = 42U;
#endif
// Generated using gaussfir(0.5, 4, 5) in MATLAB
static q15_t GMSK_FILTER[] = {8, 104, 760, 3158, 7421, 9866, 7421, 3158, 760, 104, 8, 0};
@ -32,95 +43,30 @@ const uint16_t GMSK_FILTER_LEN = 12U;
const uint16_t DC_OFFSET = 2048U;
const uint16_t TX_BUFFER_SIZE = 501U;
const uint16_t RX_BUFFER_SIZE = 601U;
#if defined(__SAM3X8E__)
// An Arduino Due
#if defined(ARDUINO_DUE_PAPA)
#define PIN_COS 7
#define PIN_PTT 8
#define PIN_COSLED 11
#define ADC_CHER_Chan (1<<7) // ADC on Due pin A0 - Due AD7 - (1 << 7)
#define ADC_ISR_EOC_Chan ADC_ISR_EOC7
#define ADC_CDR_Chan 7
#define DACC_MR_USER_SEL_Chan DACC_MR_USER_SEL_CHANNEL0 // DAC on Due DAC0
#define DACC_CHER_Chan DACC_CHER_CH0
#elif defined(ARDUINO_DUE_ZUM)
#define PIN_COS 52
#define PIN_PTT 23
#define PIN_COSLED 22
#define ADC_CHER_Chan (1<<13) // ADC on Due pin A11 - Due AD13 - (1 << 13) (PB20)
#define ADC_ISR_EOC_Chan ADC_ISR_EOC13
#define ADC_CDR_Chan 13
#define DACC_MR_USER_SEL_Chan DACC_MR_USER_SEL_CHANNEL1 // DAC on Due DAC1
#define DACC_CHER_Chan DACC_CHER_CH1
#elif defined(ARDUINO_DUE_NTH)
#define PIN_COS A7
#define PIN_PTT A8
#define PIN_COSLED A11
#define ADC_CHER_Chan (1<<7) // ADC on Due pin A0 - Due AD7 - (1 << 7)
#define ADC_ISR_EOC_Chan ADC_ISR_EOC7
#define ADC_CDR_Chan 7
#define DACC_MR_USER_SEL_Chan DACC_MR_USER_SEL_CHANNEL0 // DAC on Due DAC0
#define DACC_CHER_Chan DACC_CHER_CH0
#else
#error "Either ARDUINO_DUE_PAPA, ARDUINO_DUE_ZUM, or ARDUINO_DUE_NTH need to be defined"
#endif
#elif defined(__MK20DX256__)
// A Teensy 3.1/3.2
#define PIN_COS 14
#define PIN_PTT 15
#define PIN_COSLED 13
#elif defined(__MBED__)
// A generic MBED platform
#define PIN_COS PC_1
#define PIN_PTT PA_1
#define PIN_COSLED PB_0
#define PIN_ADC PA_0
#define PIN_DAC PA_2
#else
#error "Unknown hardware type"
#endif
extern "C" {
void ADC_Handler()
{
#if defined(__SAM3X8E__)
if (ADC->ADC_ISR & ADC_ISR_EOC_Chan) // Ensure there was an End-of-Conversion and we read the ISR reg
io.interrupt();
#elif defined(__MK20DX256__)
#elif defined(__MBED__)
io.interrupt();
#endif
}
}
CIO::CIO() :
#if defined(__MBED__)
m_pinPTT(PIN_PTT),
m_pinCOSLED(PIN_COSLED),
m_pinLED(LED1),
m_pinADC(PIN_ADC),
m_pinDAC(PIN_DAC),
m_ticker(),
#endif
m_started(false),
m_rxBuffer(RX_BUFFER_SIZE),
m_txBuffer(TX_BUFFER_SIZE),
m_rxBuffer(RX_RINGBUFFER_SIZE),
m_txBuffer(TX_RINGBUFFER_SIZE),
m_rssiBuffer(RX_RINGBUFFER_SIZE),
m_C4FSKFilter(),
m_GMSKFilter(),
m_C4FSKState(),
m_GMSKState(),
m_pttInvert(false),
m_rxLevel(128 * 128),
m_txLevel(128 * 128),
m_cwIdTXLevel(128 * 128),
m_dstarTXLevel(128 * 128),
m_dmrTXLevel(128 * 128),
m_ysfTXLevel(128 * 128),
m_p25TXLevel(128 * 128),
m_ledCount(0U),
m_ledValue(true),
m_dcd(false),
m_overflow(0U),
m_overcount(0U),
m_watchdog(0U)
m_detect(false),
m_adcOverflow(0U),
m_dacOverflow(0U),
m_count(0U),
m_watchdog(0U),
m_lockout(false)
{
::memset(m_C4FSKState, 0x00U, 70U * sizeof(q15_t));
::memset(m_GMSKState, 0x00U, 40U * sizeof(q15_t));
@ -133,12 +79,7 @@ m_watchdog(0U)
m_GMSKFilter.pState = m_GMSKState;
m_GMSKFilter.pCoeffs = GMSK_FILTER;
#if !defined(__MBED__)
// Set up the TX, COS and LED pins
pinMode(PIN_PTT, OUTPUT);
pinMode(PIN_COSLED, OUTPUT);
pinMode(PIN_LED, OUTPUT);
#endif
initInt();
}
void CIO::start()
@ -146,63 +87,12 @@ void CIO::start()
if (m_started)
return;
#if defined(__SAM3X8E__)
if (ADC->ADC_ISR & ADC_ISR_EOC_Chan) // Ensure there was an End-of-Conversion and we read the ISR reg
io.interrupt();
// Set up the ADC
NVIC_EnableIRQ(ADC_IRQn); // Enable ADC interrupt vector
ADC->ADC_IDR = 0xFFFFFFFF; // Disable interrupts
ADC->ADC_IER = ADC_CHER_Chan; // Enable End-Of-Conv interrupt
ADC->ADC_CHDR = 0xFFFF; // Disable all channels
ADC->ADC_CHER = ADC_CHER_Chan; // Enable just one channel
ADC->ADC_CGR = 0x15555555; // All gains set to x1
ADC->ADC_COR = 0x00000000; // All offsets off
ADC->ADC_MR = (ADC->ADC_MR & 0xFFFFFFF0) | (1 << 1) | ADC_MR_TRGEN; // 1 = trig source TIO from TC0
// Set up the timer
pmc_enable_periph_clk(TC_INTERFACE_ID + 0*3+0) ; // Clock the TC0 channel 0
TcChannel* t = &(TC0->TC_CHANNEL)[0]; // Pointer to TC0 registers for its channel 0
t->TC_CCR = TC_CCR_CLKDIS; // Disable internal clocking while setup regs
t->TC_IDR = 0xFFFFFFFF; // Disable interrupts
t->TC_SR; // Read int status reg to clear pending
t->TC_CMR = TC_CMR_TCCLKS_TIMER_CLOCK1 | // Use TCLK1 (prescale by 2, = 42MHz)
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC | // Count-up PWM using RC as threshold
TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR;
t->TC_RC = 1750; // Counter resets on RC, so sets period in terms of 42MHz clock (was 875)
t->TC_RA = 880; // Roughly square wave (was 440)
t->TC_CMR = (t->TC_CMR & 0xFFF0FFFF) | TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET; // Set clear and set from RA and RC compares
t->TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG ; // re-enable local clocking and switch to hardware trigger source.
// Set up the DAC
pmc_enable_periph_clk(DACC_INTERFACE_ID); // Start clocking DAC
DACC->DACC_CR = DACC_CR_SWRST; // Reset DAC
DACC->DACC_MR =
DACC_MR_TRGEN_EN | DACC_MR_TRGSEL(1) | // Trigger 1 = TIO output of TC0
DACC_MR_USER_SEL_Chan | // Select channel
(24 << DACC_MR_STARTUP_Pos); // 24 = 1536 cycles which I think is in range 23..45us since DAC clock = 42MHz
DACC->DACC_IDR = 0xFFFFFFFF; // No interrupts
DACC->DACC_CHER = DACC_CHER_Chan; // Enable channel
digitalWrite(PIN_PTT, m_pttInvert ? HIGH : LOW);
digitalWrite(PIN_COSLED, LOW);
digitalWrite(PIN_LED, HIGH);
#elif defined(__MK20DX256__)
digitalWrite(PIN_PTT, m_pttInvert ? HIGH : LOW);
digitalWrite(PIN_COSLED, LOW);
digitalWrite(PIN_LED, HIGH);
#elif defined(__MBED__)
m_ticker.attach(&ADC_Handler, 1.0 / 24000.0);
m_pinPTT.write(m_pttInvert ? 1 : 0);
m_pinCOSLED.write(0);
m_pinLED.write(1);
#endif
startInt();
m_count = 0U;
m_started = true;
setMode();
}
void CIO::process()
@ -212,9 +102,10 @@ void CIO::process()
// Two seconds timeout
if (m_watchdog >= 48000U) {
if (m_modemState == STATE_DSTAR || m_modemState == STATE_DMR || m_modemState == STATE_YSF) {
if (m_modemState == STATE_DMR)
if (m_modemState == STATE_DMR && m_tx)
dmrTX.setStart(false);
m_modemState = STATE_IDLE;
setMode();
}
m_watchdog = 0U;
@ -223,128 +114,189 @@ void CIO::process()
if (m_ledCount >= 24000U) {
m_ledCount = 0U;
m_ledValue = !m_ledValue;
#if defined(__MBED__)
m_pinLED.write(m_ledValue ? 1 : 0);
#else
digitalWrite(PIN_LED, m_ledValue ? HIGH : LOW);
#endif
setLEDInt(m_ledValue);
}
} else {
if (m_ledCount >= 240000U) {
m_ledCount = 0U;
m_ledValue = !m_ledValue;
#if defined(__MBED__)
m_pinLED.write(m_ledValue ? 1 : 0);
#else
digitalWrite(PIN_LED, m_ledValue ? HIGH : LOW);
#endif
setLEDInt(m_ledValue);
}
return;
}
#if defined(USE_COS_AS_LOCKOUT)
m_lockout = getCOSInt();
#endif
// Switch off the transmitter if needed
if (m_txBuffer.getData() == 0U && m_tx) {
m_tx = false;
#if defined(__MBED__)
m_pinPTT.write(m_pttInvert ? 1 : 0);
#else
digitalWrite(PIN_PTT, m_pttInvert ? HIGH : LOW);
#endif
setPTTInt(m_pttInvert ? true : false);
}
if (m_rxBuffer.getData() >= RX_BLOCK_SIZE) {
q15_t samples[RX_BLOCK_SIZE];
uint8_t control[RX_BLOCK_SIZE];
q15_t samples[RX_BLOCK_SIZE + 1U];
uint8_t control[RX_BLOCK_SIZE + 1U];
uint16_t rssi[RX_BLOCK_SIZE + 1U];
uint8_t blockSize = RX_BLOCK_SIZE;
for (uint16_t i = 0U; i < RX_BLOCK_SIZE; i++) {
uint16_t sample;
m_rxBuffer.get(sample, control[i]);
m_rssiBuffer.get(rssi[i]);
// Detect ADC overflow
if (m_dcd && (sample == 0U || sample == 4095U))
m_overflow++;
m_overcount++;
if (m_detect && (sample == 0U || sample == 4095U))
m_adcOverflow++;
q15_t res1 = q15_t(sample) - DC_OFFSET;
q31_t res2 = res1 * m_rxLevel;
samples[i] = q15_t(__SSAT((res2 >> 15), 16));
}
// Handle the case of the oscillator not being accurate enough
if (m_sampleCount > 0U) {
m_count += RX_BLOCK_SIZE;
if (m_count >= m_sampleCount) {
if (m_sampleInsert) {
blockSize++;
samples[RX_BLOCK_SIZE] = 0;
for (int8_t i = RX_BLOCK_SIZE - 1; i >= 0; i--)
control[i + 1] = control[i];
} else {
blockSize--;
for (uint8_t i = 0U; i < (RX_BLOCK_SIZE - 1U); i++)
control[i] = control[i + 1U];
}
m_count -= m_sampleCount;
}
}
if (m_lockout)
return;
if (m_modemState == STATE_IDLE) {
if (m_dstarEnable) {
q15_t GMSKVals[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_GMSKFilter, samples, GMSKVals, RX_BLOCK_SIZE);
q15_t GMSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_GMSKFilter, samples, GMSKVals, blockSize);
dstarRX.samples(GMSKVals, RX_BLOCK_SIZE);
dstarRX.samples(GMSKVals, rssi, blockSize);
}
if (m_dmrEnable || m_ysfEnable) {
q15_t C4FSKVals[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, RX_BLOCK_SIZE);
if (m_dmrEnable || m_ysfEnable || m_p25Enable) {
q15_t C4FSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, blockSize);
if (m_dmrEnable)
dmrIdleRX.samples(C4FSKVals, RX_BLOCK_SIZE);
if (m_dmrEnable) {
if (m_duplex)
dmrIdleRX.samples(C4FSKVals, blockSize);
else
dmrDMORX.samples(C4FSKVals, rssi, blockSize);
}
if (m_ysfEnable)
ysfRX.samples(C4FSKVals, RX_BLOCK_SIZE);
ysfRX.samples(C4FSKVals, rssi, blockSize);
if (m_p25Enable)
p25RX.samples(C4FSKVals, rssi, blockSize);
}
} else if (m_modemState == STATE_DSTAR) {
if (m_dstarEnable) {
q15_t GMSKVals[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_GMSKFilter, samples, GMSKVals, RX_BLOCK_SIZE);
q15_t GMSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_GMSKFilter, samples, GMSKVals, blockSize);
dstarRX.samples(GMSKVals, RX_BLOCK_SIZE);
dstarRX.samples(GMSKVals, rssi, blockSize);
}
} else if (m_modemState == STATE_DMR) {
if (m_dmrEnable) {
q15_t C4FSKVals[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, RX_BLOCK_SIZE);
q15_t C4FSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, blockSize);
// If the transmitter isn't on, use the DMR idle RX to detect the wakeup CSBKs
if (m_tx)
dmrRX.samples(C4FSKVals, control, RX_BLOCK_SIZE);
else
dmrIdleRX.samples(C4FSKVals, RX_BLOCK_SIZE);
if (m_duplex) {
// If the transmitter isn't on, use the DMR idle RX to detect the wakeup CSBKs
if (m_tx)
dmrRX.samples(C4FSKVals, rssi, control, blockSize);
else
dmrIdleRX.samples(C4FSKVals, blockSize);
} else {
dmrDMORX.samples(C4FSKVals, rssi, blockSize);
}
}
} else if (m_modemState == STATE_YSF) {
if (m_ysfEnable) {
q15_t C4FSKVals[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, RX_BLOCK_SIZE);
q15_t C4FSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, blockSize);
ysfRX.samples(C4FSKVals, RX_BLOCK_SIZE);
ysfRX.samples(C4FSKVals, rssi, blockSize);
}
} else if (m_modemState == STATE_CALIBRATE) {
q15_t GMSKVals[RX_BLOCK_SIZE];
::arm_fir_fast_q15(&m_GMSKFilter, samples, GMSKVals, RX_BLOCK_SIZE);
} else if (m_modemState == STATE_P25) {
if (m_p25Enable) {
q15_t C4FSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_C4FSKFilter, samples, C4FSKVals, blockSize);
calRX.samples(GMSKVals, RX_BLOCK_SIZE);
p25RX.samples(C4FSKVals, rssi, blockSize);
}
} else if (m_modemState == STATE_DSTARCAL) {
q15_t GMSKVals[RX_BLOCK_SIZE + 1U];
::arm_fir_fast_q15(&m_GMSKFilter, samples, GMSKVals, blockSize);
calDStarRX.samples(GMSKVals, blockSize);
} else if (m_modemState == STATE_RSSICAL) {
calRSSI.samples(rssi, blockSize);
}
}
}
void CIO::write(q15_t* samples, uint16_t length, const uint8_t* control)
void CIO::write(MMDVM_STATE mode, q15_t* samples, uint16_t length, const uint8_t* control)
{
if (!m_started)
return;
if (m_lockout)
return;
// Switch the transmitter on if needed
if (!m_tx) {
m_tx = true;
#if defined(__MBED__)
m_pinPTT.write(m_pttInvert ? 0 : 1);
#else
digitalWrite(PIN_PTT, m_pttInvert ? LOW : HIGH);
#endif
setPTTInt(m_pttInvert ? false : true);
}
q15_t txLevel = 0;
switch (mode) {
case STATE_DSTAR:
txLevel = m_dstarTXLevel;
break;
case STATE_DMR:
txLevel = m_dmrTXLevel;
break;
case STATE_YSF:
txLevel = m_ysfTXLevel;
break;
case STATE_P25:
txLevel = m_p25TXLevel;
break;
default:
txLevel = m_cwIdTXLevel;
break;
}
for (uint16_t i = 0U; i < length; i++) {
q31_t res1 = samples[i] * m_txLevel;
q31_t res1 = samples[i] * txLevel;
q15_t res2 = q15_t(__SSAT((res1 >> 15), 16));
uint16_t res3 = uint16_t(res2 + DC_OFFSET);
// Detect DAC overflow
if (res3 > 4095U)
m_dacOverflow++;
if (control == NULL)
m_txBuffer.put(uint16_t(res2 + DC_OFFSET), MARK_NONE);
m_txBuffer.put(res3, MARK_NONE);
else
m_txBuffer.put(uint16_t(res2 + DC_OFFSET), control[i]);
m_txBuffer.put(res3, control[i]);
}
}
@ -353,66 +305,63 @@ uint16_t CIO::getSpace() const
return m_txBuffer.getSpace();
}
void CIO::interrupt()
{
uint8_t control = MARK_NONE;
uint16_t sample = DC_OFFSET;
m_txBuffer.get(sample, control);
#if defined(__SAM3X8E__)
DACC->DACC_CDR = sample;
sample = ADC->ADC_CDR[ADC_CDR_Chan];
#elif defined(__MK20DX256__)
#elif defined(__MBED__)
m_pinDAC.write_u16(sample);
sample = m_pinADC.read_u16();
#endif
m_rxBuffer.put(sample, control);
m_watchdog++;
}
void CIO::setDecode(bool dcd)
{
if (dcd != m_dcd)
#if defined(__MBED__)
m_pinCOSLED.write(dcd ? 1 : 0);
#elif defined(PIN_COSLED)
digitalWrite(PIN_COSLED, dcd ? HIGH : LOW);
#endif
setCOSInt(dcd ? true : false);
m_dcd = dcd;
}
void CIO::setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t txLevel)
void CIO::setADCDetection(bool detect)
{
m_detect = detect;
}
void CIO::setMode()
{
#if defined(ARDUINO_MODE_PINS)
setDStarInt(m_modemState == STATE_DSTAR);
setDMRInt(m_modemState == STATE_DMR);
setYSFInt(m_modemState == STATE_YSF);
setP25Int(m_modemState == STATE_P25);
#endif
}
void CIO::setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t cwIdTXLevel, uint8_t dstarTXLevel, uint8_t dmrTXLevel, uint8_t ysfTXLevel, uint8_t p25TXLevel)
{
m_pttInvert = pttInvert;
m_rxLevel = q15_t(rxLevel * 128);
m_txLevel = q15_t(txLevel * 128);
m_rxLevel = q15_t(rxLevel * 128);
m_cwIdTXLevel = q15_t(cwIdTXLevel * 128);
m_dstarTXLevel = q15_t(dstarTXLevel * 128);
m_dmrTXLevel = q15_t(dmrTXLevel * 128);
m_ysfTXLevel = q15_t(ysfTXLevel * 128);
m_p25TXLevel = q15_t(p25TXLevel * 128);
if (rxInvert)
m_rxLevel = -m_rxLevel;
if (txInvert)
m_txLevel = -m_txLevel;
if (txInvert) {
m_dstarTXLevel = -m_dstarTXLevel;
m_dmrTXLevel = -m_dmrTXLevel;
m_ysfTXLevel = -m_ysfTXLevel;
m_p25TXLevel = -m_p25TXLevel;
}
}
bool CIO::hasADCOverflow()
void CIO::getOverflow(bool& adcOverflow, bool& dacOverflow)
{
bool overflow = m_overflow > 0U;
adcOverflow = m_adcOverflow > 0U;
dacOverflow = m_dacOverflow > 0U;
#if defined(WANT_DEBUG)
if (m_overflow > 0U)
DEBUG3("IO: Overflow, n/count", m_overflow, m_overcount);
if (m_adcOverflow > 0U || m_dacOverflow > 0U)
DEBUG3("IO: adc/dac", m_adcOverflow, m_dacOverflow);
#endif
m_overflow = 0U;
m_overcount = 0U;
return overflow;
m_adcOverflow = 0U;
m_dacOverflow = 0U;
}
bool CIO::hasTXOverflow()
@ -430,3 +379,8 @@ void CIO::resetWatchdog()
m_watchdog = 0U;
}
bool CIO::hasLockout() const
{
return m_lockout;
}

56
IO.h
View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -22,6 +22,7 @@
#include "Globals.h"
#include "SampleRB.h"
#include "RSSIRB.h"
class CIO {
public:
@ -31,39 +32,33 @@ public:
void process();
void write(q15_t* samples, uint16_t length, const uint8_t* control = NULL);
void write(MMDVM_STATE mode, q15_t* samples, uint16_t length, const uint8_t* control = NULL);
uint16_t getSpace() const;
void setDecode(bool dcd);
void setADCDetection(bool detect);
void setMode();
void interrupt();
void setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t txLevel);
void setParameters(bool rxInvert, bool txInvert, bool pttInvert, uint8_t rxLevel, uint8_t cwIdTXLevel, uint8_t dstarTXLevel, uint8_t dmrTXLevel, uint8_t ysfTXLevel, uint8_t p25TXLevel);
bool hasADCOverflow();
void getOverflow(bool& adcOverflow, bool& dacOverflow);
bool hasTXOverflow();
bool hasRXOverflow();
bool hasLockout() const;
void resetWatchdog();
private:
#if defined(__MBED__)
DigitalOut m_pinPTT;
DigitalOut m_pinCOSLED;
DigitalOut m_pinLED;
AnalogIn m_pinADC;
AnalogOut m_pinDAC;
Ticker m_ticker;
#endif
bool m_started;
CSampleRB m_rxBuffer;
CSampleRB m_txBuffer;
CRSSIRB m_rssiBuffer;
arm_fir_instance_q15 m_C4FSKFilter;
arm_fir_instance_q15 m_GMSKFilter;
@ -72,17 +67,40 @@ private:
bool m_pttInvert;
q15_t m_rxLevel;
q15_t m_txLevel;
q15_t m_cwIdTXLevel;
q15_t m_dstarTXLevel;
q15_t m_dmrTXLevel;
q15_t m_ysfTXLevel;
q15_t m_p25TXLevel;
uint32_t m_ledCount;
bool m_ledValue;
bool m_dcd;
bool m_detect;
uint16_t m_overflow;
uint16_t m_overcount;
uint16_t m_adcOverflow;
uint16_t m_dacOverflow;
uint32_t m_count;
volatile uint32_t m_watchdog;
bool m_lockout;
// Hardware specific routines
void initInt();
void startInt();
bool getCOSInt();
void setLEDInt(bool on);
void setPTTInt(bool on);
void setCOSInt(bool on);
void setDStarInt(bool on);
void setDMRInt(bool on);
void setYSFInt(bool on);
void setP25Int(bool on);
};
#endif

229
IODue.cpp Normal file
View File

@ -0,0 +1,229 @@
/*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
* Copyright (C) 2015 by Jim Mclaughlin KI6ZUM
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "IO.h"
#if defined(__SAM3X8E__)
// An Arduino Due
#if defined(ARDUINO_DUE_PAPA)
#define PIN_COS 7
#define PIN_PTT 8
#define PIN_COSLED 11
#define PIN_DSTAR 16
#define PIN_DMR 17
#define PIN_YSF 18
#define PIN_P25 19
#define ADC_CHER_Chan (1<<7) // ADC on Due pin A0 - Due AD7 - (1 << 7)
#define ADC_ISR_EOC_Chan ADC_ISR_EOC7
#define ADC_CDR_Chan 7
#define DACC_MR_USER_SEL_Chan DACC_MR_USER_SEL_CHANNEL0 // DAC on Due DAC0
#define DACC_CHER_Chan DACC_CHER_CH0
#elif defined(ARDUINO_DUE_ZUM_V10)
#define PIN_COS 52
#define PIN_PTT 23
#define PIN_COSLED 22
#define PIN_DSTAR 9
#define PIN_DMR 8
#define PIN_YSF 7
#define PIN_P25 6
#define ADC_CHER_Chan (1<<13) // ADC on Due pin A11 - Due AD13 - (1 << 13)
#define ADC_ISR_EOC_Chan ADC_ISR_EOC13
#define ADC_CDR_Chan 13
#define DACC_MR_USER_SEL_Chan DACC_MR_USER_SEL_CHANNEL1 // DAC on Due DAC1
#define DACC_CHER_Chan DACC_CHER_CH1
#define RSSI_CHER_Chan (1<<1) // ADC on Due pin A6 - Due AD1 - (1 << 1)
#define RSSI_CDR_Chan 1
#elif defined(ARDUINO_DUE_NTH)
#define PIN_COS A7
#define PIN_PTT A8
#define PIN_COSLED A11
#define PIN_DSTAR 9
#define PIN_DMR 8
#define PIN_YSF 7
#define PIN_P25 6
#define ADC_CHER_Chan (1<<7) // ADC on Due pin A0 - Due AD7 - (1 << 7)
#define ADC_ISR_EOC_Chan ADC_ISR_EOC7
#define ADC_CDR_Chan 7
#define DACC_MR_USER_SEL_Chan DACC_MR_USER_SEL_CHANNEL0 // DAC on Due DAC0
#define DACC_CHER_Chan DACC_CHER_CH0
#define RSSI_CHER_Chan (1<<1) // ADC on Due pin A6 - Due AD1 - (1 << 1)
#define RSSI_CDR_Chan 1
#else
#error "Either ARDUINO_DUE_PAPA, ARDUINO_DUE_ZUM_V10, or ARDUINO_DUE_NTH need to be defined"
#endif
const uint16_t DC_OFFSET = 2048U;
extern "C" {
void ADC_Handler()
{
io.interrupt();
}
}
void CIO::initInt()
{
// Set up the TX, COS and LED pins
pinMode(PIN_PTT, OUTPUT);
pinMode(PIN_COSLED, OUTPUT);
pinMode(PIN_LED, OUTPUT);
pinMode(PIN_COS, INPUT);
#if defined(ARDUINO_MODE_PINS)
// Set up the mode output pins
pinMode(PIN_DSTAR, OUTPUT);
pinMode(PIN_DMR, OUTPUT);
pinMode(PIN_YSF, OUTPUT);
pinMode(PIN_P25, OUTPUT);
#endif
}
void CIO::startInt()
{
if (ADC->ADC_ISR & ADC_ISR_EOC_Chan) // Ensure there was an End-of-Conversion and we read the ISR reg
io.interrupt();
// Set up the ADC
NVIC_EnableIRQ(ADC_IRQn); // Enable ADC interrupt vector
ADC->ADC_IDR = 0xFFFFFFFF; // Disable interrupts
ADC->ADC_IER = ADC_CHER_Chan; // Enable End-Of-Conv interrupt
ADC->ADC_CHDR = 0xFFFF; // Disable all channels
ADC->ADC_CHER = ADC_CHER_Chan; // Enable rx input channel
#if defined(SEND_RSSI_DATA)
ADC->ADC_CHER |= RSSI_CHER_Chan; // and RSSI input
#endif
ADC->ADC_CGR = 0x15555555; // All gains set to x1
ADC->ADC_COR = 0x00000000; // All offsets off
ADC->ADC_MR = (ADC->ADC_MR & 0xFFFFFFF0) | (1 << 1) | ADC_MR_TRGEN; // 1 = trig source TIO from TC0
#if defined(EXTERNAL_OSC)
// Set up the external clock input on PA4 = AI5
REG_PIOA_ODR = 0x10; // Set pin as input
REG_PIOA_PDR = 0x10; // Disable PIO A bit 4
REG_PIOA_ABSR &= ~0x10; // Select A peripheral = TCLK1 Input
#endif
// Set up the timer
pmc_enable_periph_clk(TC_INTERFACE_ID + 0*3+0) ; // Clock the TC0 channel 0
TcChannel* t = &(TC0->TC_CHANNEL)[0]; // Pointer to TC0 registers for its channel 0
t->TC_CCR = TC_CCR_CLKDIS; // Disable internal clocking while setup regs
t->TC_IDR = 0xFFFFFFFF; // Disable interrupts
t->TC_SR; // Read int status reg to clear pending
#if defined(EXTERNAL_OSC)
t->TC_CMR = TC_CMR_TCCLKS_XC1 | // Use XC1 = TCLK1 external clock
#else
t->TC_CMR = TC_CMR_TCCLKS_TIMER_CLOCK1 | // Use TCLK1 (prescale by 2, = 42MHz)
#endif
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC | // Count-up PWM using RC as threshold
TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR;
#if defined(EXTERNAL_OSC)
t->TC_RC = EXTERNAL_OSC / 24000; // Counter resets on RC, so sets period in terms of the external clock
t->TC_RA = EXTERNAL_OSC / 48000; // Roughly square wave
#else
t->TC_RC = 1750; // Counter resets on RC, so sets period in terms of 42MHz internal clock
t->TC_RA = 880; // Roughly square wave
#endif
t->TC_CMR = (t->TC_CMR & 0xFFF0FFFF) | TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET; // Set clear and set from RA and RC compares
t->TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG; // re-enable local clocking and switch to hardware trigger source.
// Set up the DAC
pmc_enable_periph_clk(DACC_INTERFACE_ID); // Start clocking DAC
DACC->DACC_CR = DACC_CR_SWRST; // Reset DAC
DACC->DACC_MR =
DACC_MR_TRGEN_EN | DACC_MR_TRGSEL(1) | // Trigger 1 = TIO output of TC0
DACC_MR_USER_SEL_Chan | // Select channel
(24 << DACC_MR_STARTUP_Pos); // 24 = 1536 cycles which I think is in range 23..45us since DAC clock = 42MHz
DACC->DACC_IDR = 0xFFFFFFFF; // No interrupts
DACC->DACC_CHER = DACC_CHER_Chan; // Enable channel
digitalWrite(PIN_PTT, m_pttInvert ? HIGH : LOW);
digitalWrite(PIN_COSLED, LOW);
digitalWrite(PIN_LED, HIGH);
}
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
uint8_t control = MARK_NONE;
uint16_t sample = DC_OFFSET;
m_txBuffer.get(sample, control);
DACC->DACC_CDR = sample;
sample = ADC->ADC_CDR[ADC_CDR_Chan];
m_rxBuffer.put(sample, control);
#if defined(SEND_RSSI_DATA)
m_rssiBuffer.put(ADC->ADC_CDR[RSSI_CDR_Chan]);
#else
m_rssiBuffer.put(0U);
#endif
m_watchdog++;
}
}
bool CIO::getCOSInt()
{
return digitalRead(PIN_COS) == HIGH;
}
void CIO::setLEDInt(bool on)
{
digitalWrite(PIN_LED, on ? HIGH : LOW);
}
void CIO::setPTTInt(bool on)
{
digitalWrite(PIN_PTT, on ? HIGH : LOW);
}
void CIO::setCOSInt(bool on)
{
digitalWrite(PIN_COSLED, on ? HIGH : LOW);
}
void CIO::setDStarInt(bool on)
{
digitalWrite(PIN_DSTAR, on ? HIGH : LOW);
}
void CIO::setDMRInt(bool on)
{
digitalWrite(PIN_DMR, on ? HIGH : LOW);
}
void CIO::setYSFInt(bool on)
{
digitalWrite(PIN_YSF, on ? HIGH : LOW);
}
void CIO::setP25Int(bool on)
{
digitalWrite(PIN_P25, on ? HIGH : LOW);
}
#endif

674
IOSTM.cpp Normal file
View File

@ -0,0 +1,674 @@
/*
* Copyright (C) 2016 by Jim McLaughlin KI6ZUM
* Copyright (C) 2016, 2017 by Andy Uribe CA6JAU
* Copyright (C) 2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "IO.h"
#if defined(STM32F4XX) || defined(STM32F4)
#if defined(STM32F4_DISCOVERY)
/*
Pin definitions for STM32F4 Discovery Board:
PTT PB13 output
COSLED PA7 output
LED PD15 output
COS PA5 input
DSTAR PD12 output
DMR PD13 output
YSF PD14 output
P25 PD11 output
RX PA0 analog input
RSSI PA1 analog input
TX PA4 analog output
EXT_CLK PA15 input
*/
#define PIN_COS GPIO_Pin_5
#define PORT_COS GPIOA
#define RCC_Per_COS RCC_AHB1Periph_GPIOA
#define PIN_PTT GPIO_Pin_13
#define PORT_PTT GPIOB
#define RCC_Per_PTT RCC_AHB1Periph_GPIOB
#define PIN_COSLED GPIO_Pin_7
#define PORT_COSLED GPIOA
#define RCC_Per_COSLED RCC_AHB1Periph_GPIOA
#define PIN_LED GPIO_Pin_15
#define PORT_LED GPIOD
#define RCC_Per_LED RCC_AHB1Periph_GPIOD
#define PIN_P25 GPIO_Pin_11
#define PORT_P25 GPIOD
#define RCC_Per_P25 RCC_AHB1Periph_GPIOD
#define PIN_DSTAR GPIO_Pin_12
#define PORT_DSTAR GPIOD
#define RCC_Per_DSTAR RCC_AHB1Periph_GPIOD
#define PIN_DMR GPIO_Pin_13
#define PORT_DMR GPIOD
#define RCC_Per_DMR RCC_AHB1Periph_GPIOD
#define PIN_YSF GPIO_Pin_14
#define PORT_YSF GPIOD
#define RCC_Per_YSF RCC_AHB1Periph_GPIOD
#define PIN_EXT_CLK GPIO_Pin_15
#define SRC_EXT_CLK GPIO_PinSource15
#define PORT_EXT_CLK GPIOA
#define PIN_RX GPIO_Pin_0
#define PIN_RX_CH ADC_Channel_0
#define PORT_RX GPIOA
#define RCC_Per_RX RCC_AHB1Periph_GPIOA
#define PIN_RSSI GPIO_Pin_1
#define PIN_RSSI_CH ADC_Channel_1
#define PORT_RSSI GPIOA
#define RCC_Per_RSSI RCC_AHB1Periph_GPIOA
#define PIN_TX GPIO_Pin_4
#define PIN_TX_CH DAC_Channel_1
#elif defined(STM32F4_PI)
/*
Pin definitions for STM32F4 Pi Board:
PTT PB13 output
COSLED PB14 output
LED PB15 output
COS PC0 input
DSTAR PC7 output
DMR PC8 output
YSF PA8 output
P25 PC9 output
RX PA0 analog input
RSSI PA7 analog input
TX PA4 analog output
EXT_CLK PA15 input
*/
#define PIN_COS GPIO_Pin_0
#define PORT_COS GPIOC
#define RCC_Per_COS RCC_AHB1Periph_GPIOC
#define PIN_PTT GPIO_Pin_13
#define PORT_PTT GPIOB
#define RCC_Per_PTT RCC_AHB1Periph_GPIOB
#define PIN_COSLED GPIO_Pin_14
#define PORT_COSLED GPIOB
#define RCC_Per_COSLED RCC_AHB1Periph_GPIOB
#define PIN_LED GPIO_Pin_15
#define PORT_LED GPIOB
#define RCC_Per_LED RCC_AHB1Periph_GPIOB
#define PIN_P25 GPIO_Pin_9
#define PORT_P25 GPIOC
#define RCC_Per_P25 RCC_AHB1Periph_GPIOC
#define PIN_DSTAR GPIO_Pin_7
#define PORT_DSTAR GPIOC
#define RCC_Per_DSTAR RCC_AHB1Periph_GPIOC
#define PIN_DMR GPIO_Pin_8
#define PORT_DMR GPIOC
#define RCC_Per_DMR RCC_AHB1Periph_GPIOC
#define PIN_YSF GPIO_Pin_8
#define PORT_YSF GPIOA
#define RCC_Per_YSF RCC_AHB1Periph_GPIOA
#define PIN_EXT_CLK GPIO_Pin_15
#define SRC_EXT_CLK GPIO_PinSource15
#define PORT_EXT_CLK GPIOA
#define PIN_RX GPIO_Pin_0
#define PIN_RX_CH ADC_Channel_0
#define PORT_RX GPIOA
#define RCC_Per_RX RCC_AHB1Periph_GPIOA
#define PIN_RSSI GPIO_Pin_7
#define PIN_RSSI_CH ADC_Channel_7
#define PORT_RSSI GPIOA
#define RCC_Per_RSSI RCC_AHB1Periph_GPIOA
#define PIN_TX GPIO_Pin_4
#define PIN_TX_CH DAC_Channel_1
#elif defined(STM32F4_NUCLEO)
#if defined(STM32F4_NUCLEO_MORPHO_HEADER)
/*
Pin definitions for STM32F4 Nucleo boards (ST Morpho header):
PTT PB13 output
COSLED PB14 output
LED PA5 output
COS PB15 input
DSTAR PB10 output
DMR PB4 output
YSF PB5 output
P25 PB3 output
MDSTAR PC4 output
MDMR PC5 outout
MYSF PC2 output
MP25 PC3 output
RX PA0 analog input
RSSI PA1 analog input
TX PA4 analog output
EXT_CLK PA15 input
*/
#define PIN_COS GPIO_Pin_15
#define PORT_COS GPIOB
#define RCC_Per_COS RCC_AHB1Periph_GPIOB
#define PIN_PTT GPIO_Pin_13
#define PORT_PTT GPIOB
#define RCC_Per_PTT RCC_AHB1Periph_GPIOB
#define PIN_COSLED GPIO_Pin_14
#define PORT_COSLED GPIOB
#define RCC_Per_COSLED RCC_AHB1Periph_GPIOB
#define PIN_LED GPIO_Pin_5
#define PORT_LED GPIOA
#define RCC_Per_LED RCC_AHB1Periph_GPIOA
#define PIN_P25 GPIO_Pin_3
#define PORT_P25 GPIOB
#define RCC_Per_P25 RCC_AHB1Periph_GPIOB
#define PIN_DSTAR GPIO_Pin_10
#define PORT_DSTAR GPIOB
#define RCC_Per_DSTAR RCC_AHB1Periph_GPIOB
#define PIN_DMR GPIO_Pin_4
#define PORT_DMR GPIOB
#define RCC_Per_DMR RCC_AHB1Periph_GPIOB
#define PIN_YSF GPIO_Pin_5
#define PORT_YSF GPIOB
#define RCC_Per_YSF RCC_AHB1Periph_GPIOB
#if defined(STM32F4_NUCLEO_MODE_PINS)
#define PIN_MP25 GPIO_Pin_3
#define PORT_MP25 GPIOC
#define RCC_Per_MP25 RCC_AHB1Periph_GPIOC
#define PIN_MDSTAR GPIO_Pin_4
#define PORT_MDSTAR GPIOC
#define RCC_Per_MDSTAR RCC_AHB1Periph_GPIOC
#define PIN_MDMR GPIO_Pin_5
#define PORT_MDMR GPIOC
#define RCC_Per_MDMR RCC_AHB1Periph_GPIOC
#define PIN_MYSF GPIO_Pin_2
#define PORT_MYSF GPIOC
#define RCC_Per_MYSF RCC_AHB1Periph_GPIOC
#endif
#define PIN_EXT_CLK GPIO_Pin_15
#define SRC_EXT_CLK GPIO_PinSource15
#define PORT_EXT_CLK GPIOA
#define PIN_RX GPIO_Pin_0
#define PIN_RX_CH ADC_Channel_0
#define PORT_RX GPIOA
#define RCC_Per_RX RCC_AHB1Periph_GPIOA
#define PIN_RSSI GPIO_Pin_1
#define PIN_RSSI_CH ADC_Channel_1
#define PORT_RSSI GPIOA
#define RCC_Per_RSSI RCC_AHB1Periph_GPIOA
#define PIN_TX GPIO_Pin_4
#define PIN_TX_CH DAC_Channel_1
#elif defined(STM32F4_NUCLEO_ARDUINO_HEADER)
/*
Pin definitions for STM32F4 Nucleo boards (Arduino header):
PTT PB10 output
COSLED PB3 output
LED PB5 output
COS PB4 input
DSTAR PA1 output
DMR PA4 output
YSF PB0 output
P25 PC1 output
RX PA0 analog input
RSSI PC0 analog input
TX PA5 analog output
EXT_CLK PB8 input
*/
#define PIN_COS GPIO_Pin_4
#define PORT_COS GPIOB
#define RCC_Per_COS RCC_AHB1Periph_GPIOB
#define PIN_PTT GPIO_Pin_10
#define PORT_PTT GPIOB
#define RCC_Per_PTT RCC_AHB1Periph_GPIOB
#define PIN_COSLED GPIO_Pin_3
#define PORT_COSLED GPIOB
#define RCC_Per_COSLED RCC_AHB1Periph_GPIOB
#define PIN_LED GPIO_Pin_5
#define PORT_LED GPIOB
#define RCC_Per_LED RCC_AHB1Periph_GPIOB
#define PIN_P25 GPIO_Pin_1
#define PORT_P25 GPIOC
#define RCC_Per_P25 RCC_AHB1Periph_GPIOC
#define PIN_DSTAR GPIO_Pin_1
#define PORT_DSTAR GPIOA
#define RCC_Per_DSTAR RCC_AHB1Periph_GPIOA
#define PIN_DMR GPIO_Pin_4
#define PORT_DMR GPIOA
#define RCC_Per_DMR RCC_AHB1Periph_GPIOA
#define PIN_YSF GPIO_Pin_0
#define PORT_YSF GPIOB
#define RCC_Per_YSF RCC_AHB1Periph_GPIOB
#define PIN_EXT_CLK GPIO_Pin_8
#define SRC_EXT_CLK GPIO_PinSource8
#define PORT_EXT_CLK GPIOB
#define PIN_RX GPIO_Pin_0
#define PIN_RX_CH ADC_Channel_0
#define PORT_RX GPIOA
#define RCC_Per_RX RCC_AHB1Periph_GPIOA
#define PIN_RSSI GPIO_Pin_0
#define PIN_RSSI_CH ADC_Channel_10
#define PORT_RSSI GPIOC
#define RCC_Per_RSSI RCC_AHB1Periph_GPIOC
#define PIN_TX GPIO_Pin_5
#define PIN_TX_CH DAC_Channel_2
#else
#error "Either STM32F4_NUCLEO_MORPHO_HEADER or STM32F4_NUCLEO_ARDUINO_HEADER need to be defined in Config.h"
#endif
#else
#error "Either STM32F4_DISCOVERY, STM32F4_PI or STM32F4_NUCLEO need to be defined"
#endif
const uint16_t DC_OFFSET = 2048U;
// Sampling frequency
#define SAMP_FREQ 24000
extern "C" {
void TIM2_IRQHandler() {
if (TIM_GetITStatus(TIM2, TIM_IT_Update) != RESET) {
TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
io.interrupt();
}
}
}
void CIO::initInt()
{
GPIO_InitTypeDef GPIO_InitStruct;
GPIO_StructInit(&GPIO_InitStruct);
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStruct.GPIO_OType = GPIO_OType_PP;
GPIO_InitStruct.GPIO_PuPd = GPIO_PuPd_DOWN;
// PTT pin
RCC_AHB1PeriphClockCmd(RCC_Per_PTT, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_PTT;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_PTT, &GPIO_InitStruct);
// COSLED pin
RCC_AHB1PeriphClockCmd(RCC_Per_COSLED, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_COSLED;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_COSLED, &GPIO_InitStruct);
// LED pin
RCC_AHB1PeriphClockCmd(RCC_Per_LED, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_LED;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_LED, &GPIO_InitStruct);
// Init the input pins PIN_COS
RCC_AHB1PeriphClockCmd(RCC_Per_COS, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_COS;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IN;
GPIO_Init(PORT_COS, &GPIO_InitStruct);
#if defined(ARDUINO_MODE_PINS)
// DSTAR pin
RCC_AHB1PeriphClockCmd(RCC_Per_DSTAR, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_DSTAR;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_DSTAR, &GPIO_InitStruct);
// DMR pin
RCC_AHB1PeriphClockCmd(RCC_Per_DMR, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_DMR;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_DMR, &GPIO_InitStruct);
// YSF pin
RCC_AHB1PeriphClockCmd(RCC_Per_YSF, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_YSF;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_YSF, &GPIO_InitStruct);
// P25 pin
RCC_AHB1PeriphClockCmd(RCC_Per_P25, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_P25;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_P25, &GPIO_InitStruct);
#endif
#if defined(STM32F4_NUCLEO_MODE_PINS) && defined(STM32F4_NUCLEO_MORPHO_HEADER) && defined(STM32F4_NUCLEO)
// DSTAR mode pin
RCC_AHB1PeriphClockCmd(RCC_Per_MDSTAR, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_MDSTAR;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_MDSTAR, &GPIO_InitStruct);
// DMR mode pin
RCC_AHB1PeriphClockCmd(RCC_Per_MDMR, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_MDMR;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_MDMR, &GPIO_InitStruct);
// YSF mode pin
RCC_AHB1PeriphClockCmd(RCC_Per_MYSF, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_MYSF;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_MYSF, &GPIO_InitStruct);
// P25 mode pin
RCC_AHB1PeriphClockCmd(RCC_Per_MP25, ENABLE);
GPIO_InitStruct.GPIO_Pin = PIN_MP25;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_OUT;
GPIO_Init(PORT_MP25, &GPIO_InitStruct);
#endif
}
void CIO::startInt()
{
if ((ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC) != RESET))
io.interrupt();
// Init the ADC
GPIO_InitTypeDef GPIO_InitStruct;
ADC_InitTypeDef ADC_InitStructure;
ADC_CommonInitTypeDef ADC_CommonInitStructure;
GPIO_StructInit(&GPIO_InitStruct);
ADC_CommonStructInit(&ADC_CommonInitStructure);
ADC_StructInit(&ADC_InitStructure);
// Enable ADC1 clock
RCC_AHB1PeriphClockCmd(RCC_Per_RX, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
// Enable ADC1 GPIO
GPIO_InitStruct.GPIO_Pin = PIN_RX;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL ;
GPIO_Init(PORT_RX, &GPIO_InitStruct);
#if defined(SEND_RSSI_DATA)
// Enable ADC2 clock
RCC_AHB1PeriphClockCmd(RCC_Per_RSSI, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC2, ENABLE);
// Enable ADC2 GPIO
GPIO_InitStruct.GPIO_Pin = PIN_RSSI;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL ;
GPIO_Init(PORT_RSSI, &GPIO_InitStruct);
#endif
// Init ADCs in dual mode (RSSI), div clock by two
#if defined(SEND_RSSI_DATA)
ADC_CommonInitStructure.ADC_Mode = ADC_DualMode_RegSimult;
#else
ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
#endif
ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div2;
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
ADC_CommonInit(&ADC_CommonInitStructure);
// Init ADC1 and ADC2: 12bit, single-conversion
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ScanConvMode = DISABLE;
ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
ADC_InitStructure.ADC_ExternalTrigConvEdge = 0;
ADC_InitStructure.ADC_ExternalTrigConv = 0;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = 1;
ADC_Init(ADC1, &ADC_InitStructure);
ADC_EOCOnEachRegularChannelCmd(ADC1, ENABLE);
ADC_RegularChannelConfig(ADC1, PIN_RX_CH, 1, ADC_SampleTime_3Cycles);
// Enable ADC1
ADC_Cmd(ADC1, ENABLE);
#if defined(SEND_RSSI_DATA)
ADC_Init(ADC2, &ADC_InitStructure);
ADC_EOCOnEachRegularChannelCmd(ADC2, ENABLE);
ADC_RegularChannelConfig(ADC2, PIN_RSSI_CH, 1, ADC_SampleTime_3Cycles);
// Enable ADC2
ADC_Cmd(ADC2, ENABLE);
#endif
// Init the DAC
DAC_InitTypeDef DAC_InitStructure;
GPIO_StructInit(&GPIO_InitStruct);
DAC_StructInit(&DAC_InitStructure);
// GPIOA clock enable
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
// DAC Periph clock enable
RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
// GPIO CONFIGURATION of DAC Pin
GPIO_InitStruct.GPIO_Pin = PIN_TX;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStruct.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(GPIOA, &GPIO_InitStruct);
DAC_InitStructure.DAC_Trigger = DAC_Trigger_None;
DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_None;
DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable;
DAC_Init(PIN_TX_CH, &DAC_InitStructure);
DAC_Cmd(PIN_TX_CH, ENABLE);
// Init the timer
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
#if defined(EXTERNAL_OSC)
// Configure a GPIO as external TIM2 clock source
GPIO_PinAFConfig(PORT_EXT_CLK, SRC_EXT_CLK, GPIO_AF_TIM2);
GPIO_InitStruct.GPIO_Pin = PIN_EXT_CLK;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AF;
GPIO_Init(PORT_EXT_CLK, &GPIO_InitStruct);
#endif
TIM_TimeBaseInitTypeDef timerInitStructure;
TIM_TimeBaseStructInit (&timerInitStructure);
// TIM2 output frequency
#if defined(EXTERNAL_OSC)
timerInitStructure.TIM_Prescaler = (uint16_t) ((EXTERNAL_OSC/(2*SAMP_FREQ)) - 1);
#else
timerInitStructure.TIM_Prescaler = (uint16_t) ((SystemCoreClock/(4*SAMP_FREQ)) - 1);
#endif
timerInitStructure.TIM_CounterMode = TIM_CounterMode_Up;
timerInitStructure.TIM_Period = 1;
timerInitStructure.TIM_ClockDivision = TIM_CKD_DIV1;
timerInitStructure.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM2, &timerInitStructure);
#if defined(EXTERNAL_OSC)
// Enable external clock
TIM_ETRClockMode2Config(TIM2, TIM_ExtTRGPSC_OFF, TIM_ExtTRGPolarity_NonInverted, 0x00);
#else
// Enable internal clock
TIM_InternalClockConfig(TIM2);
#endif
// Enable TIM2
TIM_Cmd(TIM2, ENABLE);
// Enable TIM2 interrupt
TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
NVIC_InitTypeDef nvicStructure;
nvicStructure.NVIC_IRQChannel = TIM2_IRQn;
nvicStructure.NVIC_IRQChannelPreemptionPriority = 0;
nvicStructure.NVIC_IRQChannelSubPriority = 1;
nvicStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvicStructure);
GPIO_ResetBits(PORT_COSLED, PIN_COSLED);
GPIO_SetBits(PORT_LED, PIN_LED);
}
void CIO::interrupt()
{
uint8_t control = MARK_NONE;
uint16_t sample = DC_OFFSET;
uint16_t rawRSSI = 0U;
m_txBuffer.get(sample, control);
// Send the value to the DAC
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
DAC_SetChannel2Data(DAC_Align_12b_R, sample);
#else
DAC_SetChannel1Data(DAC_Align_12b_R, sample);
#endif
// Read value from ADC1 and ADC2
if ((ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC) == RESET)) {
// shouldn't be still in reset at this point so null the sample value?
sample = 0U;
} else {
sample = ADC_GetConversionValue(ADC1);
#if defined(SEND_RSSI_DATA)
rawRSSI = ADC_GetConversionValue(ADC2);
#endif
}
// trigger next ADC1
ADC_ClearFlag(ADC1, ADC_FLAG_EOC);
ADC_SoftwareStartConv(ADC1);
m_rxBuffer.put(sample, control);
m_rssiBuffer.put(rawRSSI);
m_watchdog++;
}
bool CIO::getCOSInt()
{
return GPIO_ReadOutputDataBit(PORT_COS, PIN_COS) == Bit_SET;
}
void CIO::setLEDInt(bool on)
{
GPIO_WriteBit(PORT_LED, PIN_LED, on ? Bit_SET : Bit_RESET);
}
void CIO::setPTTInt(bool on)
{
GPIO_WriteBit(PORT_PTT, PIN_PTT, on ? Bit_SET : Bit_RESET);
}
void CIO::setCOSInt(bool on)
{
GPIO_WriteBit(PORT_COSLED, PIN_COSLED, on ? Bit_SET : Bit_RESET);
}
void CIO::setDStarInt(bool on)
{
GPIO_WriteBit(PORT_DSTAR, PIN_DSTAR, on ? Bit_SET : Bit_RESET);
#if defined(STM32F4_NUCLEO_MODE_PINS) && defined(STM32F4_NUCLEO_MORPHO_HEADER) && defined(STM32F4_NUCLEO)
GPIO_WriteBit(PORT_MDSTAR, PIN_MDSTAR, on ? Bit_SET : Bit_RESET);
#endif
}
void CIO::setDMRInt(bool on)
{
GPIO_WriteBit(PORT_DMR, PIN_DMR, on ? Bit_SET : Bit_RESET);
#if defined(STM32F4_NUCLEO_MODE_PINS) && defined(STM32F4_NUCLEO_MORPHO_HEADER) && defined(STM32F4_NUCLEO)
GPIO_WriteBit(PORT_MDMR, PIN_MDMR, on ? Bit_SET : Bit_RESET);
#endif
}
void CIO::setYSFInt(bool on)
{
GPIO_WriteBit(PORT_YSF, PIN_YSF, on ? Bit_SET : Bit_RESET);
#if defined(STM32F4_NUCLEO_MODE_PINS) && defined(STM32F4_NUCLEO_MORPHO_HEADER) && defined(STM32F4_NUCLEO)
GPIO_WriteBit(PORT_MYSF, PIN_MYSF, on ? Bit_SET : Bit_RESET);
#endif
}
void CIO::setP25Int(bool on)
{
GPIO_WriteBit(PORT_P25, PIN_P25, on ? Bit_SET : Bit_RESET);
#if defined(STM32F4_NUCLEO_MODE_PINS) && defined(STM32F4_NUCLEO_MORPHO_HEADER) && defined(STM32F4_NUCLEO)
GPIO_WriteBit(PORT_MP25, PIN_MP25, on ? Bit_SET : Bit_RESET);
#endif
}
#endif

213
IOTeensy.cpp Normal file
View File

@ -0,0 +1,213 @@
/*
* Copyright (C) 2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "IO.h"
#if defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
#if defined(EXTERNAL_OSC)
#define PIN_LED 3
#else
#define PIN_LED 13
#endif
#define PIN_COS 4
#define PIN_PTT 5
#define PIN_COSLED 6
#define PIN_DSTAR 9
#define PIN_DMR 10
#define PIN_YSF 11
#define PIN_P25 12
#define PIN_ADC 5 // A0, Pin 14
#define PIN_RSSI 4 // Teensy 3.5/3.6, A16, Pin 35. Teensy 3.1/3.2, A17, Pin 28
#define PDB_CHnC1_TOS 0x0100
#define PDB_CHnC1_EN 0x0001
const uint16_t DC_OFFSET = 2048U;
extern "C" {
void adc0_isr()
{
io.interrupt();
}
}
void CIO::initInt()
{
// Set up the TX, COS and LED pins
pinMode(PIN_PTT, OUTPUT);
pinMode(PIN_COSLED, OUTPUT);
pinMode(PIN_LED, OUTPUT);
pinMode(PIN_COS, INPUT);
#if defined(ARDUINO_MODE_PINS)
// Set up the mode output pins
pinMode(PIN_DSTAR, OUTPUT);
pinMode(PIN_DMR, OUTPUT);
pinMode(PIN_YSF, OUTPUT);
pinMode(PIN_P25, OUTPUT);
#endif
}
void CIO::startInt()
{
// Initialise the DAC
SIM_SCGC2 |= SIM_SCGC2_DAC0;
DAC0_C0 = DAC_C0_DACEN | DAC_C0_DACRFS; // 3.3V VDDA is DACREF_2
// Initialise ADC0
SIM_SCGC6 |= SIM_SCGC6_ADC0;
ADC0_CFG1 = ADC_CFG1_ADIV(1) | ADC_CFG1_ADICLK(1) | // Single-ended 12 bits, long sample time
ADC_CFG1_MODE(1) | ADC_CFG1_ADLSMP;
ADC0_CFG2 = ADC_CFG2_MUXSEL | ADC_CFG2_ADLSTS(2); // Select channels ADxxxb
ADC0_SC2 = ADC_SC2_REFSEL(0) | ADC_SC2_ADTRG; // Voltage ref external, hardware trigger
ADC0_SC3 = ADC_SC3_AVGE | ADC_SC3_AVGS(0); // Enable averaging, 4 samples
ADC0_SC3 |= ADC_SC3_CAL;
while (ADC0_SC3 & ADC_SC3_CAL) // Wait for calibration
;
uint16_t sum0 = ADC0_CLPS + ADC0_CLP4 + ADC0_CLP3 + // Plus side gain
ADC0_CLP2 + ADC0_CLP1 + ADC0_CLP0;
sum0 = (sum0 / 2U) | 0x8000U;
ADC0_PG = sum0;
ADC0_SC1A = ADC_SC1_AIEN | PIN_ADC; // Enable ADC interrupt, use A0
NVIC_ENABLE_IRQ(IRQ_ADC0);
#if defined(SEND_RSSI_DATA)
// Initialise ADC1
SIM_SCGC3 |= SIM_SCGC3_ADC1;
ADC1_CFG1 = ADC_CFG1_ADIV(1) | ADC_CFG1_ADICLK(1) | // Single-ended 12 bits, long sample time
ADC_CFG1_MODE(1) | ADC_CFG1_ADLSMP;
ADC1_CFG2 = ADC_CFG2_MUXSEL | ADC_CFG2_ADLSTS(2); // Select channels ADxxxb
ADC1_SC2 = ADC_SC2_REFSEL(0); // Voltage ref external, software trigger
ADC1_SC3 = ADC_SC3_AVGE | ADC_SC3_AVGS(0); // Enable averaging, 4 samples
ADC1_SC3 |= ADC_SC3_CAL;
while (ADC1_SC3 & ADC_SC3_CAL) // Wait for calibration
;
uint16_t sum1 = ADC1_CLPS + ADC1_CLP4 + ADC1_CLP3 + // Plus side gain
ADC1_CLP2 + ADC1_CLP1 + ADC1_CLP0;
sum1 = (sum1 / 2U) | 0x8000U;
ADC1_PG = sum1;
#endif
#if defined(EXTERNAL_OSC)
// Set ADC0 to trigger from the LPTMR at 24 kHz
SIM_SOPT7 = SIM_SOPT7_ADC0ALTTRGEN | // Enable ADC0 alternate trigger
SIM_SOPT7_ADC0TRGSEL(14); // Trigger ADC0 by LPTMR0
CORE_PIN13_CONFIG = PORT_PCR_MUX(3);
SIM_SCGC5 |= SIM_SCGC5_LPTIMER; // Enable Low Power Timer Access
LPTMR0_CSR = 0; // Disable
LPTMR0_PSR = LPTMR_PSR_PBYP; // Bypass prescaler/filter
LPTMR0_CMR = (EXTERNAL_OSC / 24000) - 1; // Frequency divided by CMR + 1
LPTMR0_CSR = LPTMR_CSR_TPS(2) | // Pin: 0=CMP0, 1=xtal, 2=pin13
LPTMR_CSR_TMS; // Mode Select, 0=timer, 1=counter
LPTMR0_CSR |= LPTMR_CSR_TEN; // Enable
#else
// Setup PDB for ADC0 at 24 kHz
SIM_SCGC6 |= SIM_SCGC6_PDB; // Enable PDB clock
PDB0_MOD = (F_BUS / 24000) - 1; // Timer period - 1
PDB0_IDLY = 0; // Interrupt delay
PDB0_CH0C1 = PDB_CHnC1_TOS | PDB_CHnC1_EN; // Enable pre-trigger for ADC0
PDB0_SC = PDB_SC_TRGSEL(15) | PDB_SC_PDBEN | // SW trigger, enable interrupts, continuous mode
PDB_SC_PDBIE | PDB_SC_CONT | PDB_SC_LDOK; // No prescaling
PDB0_SC |= PDB_SC_SWTRIG; // Software trigger (reset and restart counter)
#endif
digitalWrite(PIN_PTT, m_pttInvert ? HIGH : LOW);
digitalWrite(PIN_COSLED, LOW);
digitalWrite(PIN_LED, HIGH);
}
void CIO::interrupt()
{
uint8_t control = MARK_NONE;
uint16_t sample = DC_OFFSET;
m_txBuffer.get(sample, control);
*(int16_t *)&(DAC0_DAT0L) = sample;
if ((ADC0_SC1A & ADC_SC1_COCO) == ADC_SC1_COCO) {
sample = ADC0_RA;
m_rxBuffer.put(sample, control);
}
#if defined(SEND_RSSI_DATA)
if ((ADC1_SC1A & ADC_SC1_COCO) == ADC_SC1_COCO) {
uint16_t rssi = ADC1_RA;
m_rssiBuffer.put(rssi);
} else {
m_rssiBuffer.put(0U);
}
ADC1_SC1A = PIN_RSSI; // Start the next RSSI conversion
#else
m_rssiBuffer.put(0U);
#endif
m_watchdog++;
}
bool CIO::getCOSInt()
{
return digitalRead(PIN_COS) == HIGH;
}
void CIO::setLEDInt(bool on)
{
digitalWrite(PIN_LED, on ? HIGH : LOW);
}
void CIO::setPTTInt(bool on)
{
digitalWrite(PIN_PTT, on ? HIGH : LOW);
}
void CIO::setCOSInt(bool on)
{
digitalWrite(PIN_COSLED, on ? HIGH : LOW);
}
void CIO::setDStarInt(bool on)
{
digitalWrite(PIN_DSTAR, on ? HIGH : LOW);
}
void CIO::setDMRInt(bool on)
{
digitalWrite(PIN_DMR, on ? HIGH : LOW);
}
void CIO::setYSFInt(bool on)
{
digitalWrite(PIN_YSF, on ? HIGH : LOW);
}
void CIO::setP25Int(bool on)
{
digitalWrite(PIN_P25, on ? HIGH : LOW);
}
#endif

115
MMDVM.cpp Normal file
View File

@ -0,0 +1,115 @@
/*
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Mathis Schmieder DB9MAT
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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(STM32F4)
#include "Config.h"
#include "Globals.h"
// Global variables
MMDVM_STATE m_modemState = STATE_IDLE;
bool m_dstarEnable = true;
bool m_dmrEnable = true;
bool m_ysfEnable = true;
bool m_p25Enable = true;
bool m_duplex = true;
bool m_tx = false;
bool m_dcd = false;
uint32_t m_sampleCount = 0U;
bool m_sampleInsert = false;
CDStarRX dstarRX;
CDStarTX dstarTX;
CDMRIdleRX dmrIdleRX;
CDMRRX dmrRX;
CDMRTX dmrTX;
CDMRDMORX dmrDMORX;
CDMRDMOTX dmrDMOTX;
CYSFRX ysfRX;
CYSFTX ysfTX;
CP25RX p25RX;
CP25TX p25TX;
CCalDStarRX calDStarRX;
CCalDStarTX calDStarTX;
CCalDMR calDMR;
CCalRSSI calRSSI;
CCWIdTX cwIdTX;
CSerialPort serial;
CIO io;
void setup()
{
serial.start();
}
void loop()
{
serial.process();
io.process();
// The following is for transmitting
if (m_dstarEnable && m_modemState == STATE_DSTAR)
dstarTX.process();
if (m_dmrEnable && m_modemState == STATE_DMR) {
if (m_duplex)
dmrTX.process();
else
dmrDMOTX.process();
}
if (m_ysfEnable && m_modemState == STATE_YSF)
ysfTX.process();
if (m_p25Enable && m_modemState == STATE_P25)
p25TX.process();
if (m_modemState == STATE_DSTARCAL)
calDStarTX.process();
if (m_modemState == STATE_DMRCAL)
calDMR.process();
if (m_modemState == STATE_IDLE)
cwIdTX.process();
}
int main()
{
setup();
for (;;)
loop();
}
#endif

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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
@ -25,8 +26,15 @@ MMDVM_STATE m_modemState = STATE_IDLE;
bool m_dstarEnable = true;
bool m_dmrEnable = true;
bool m_ysfEnable = true;
bool m_p25Enable = true;
bool m_tx = false;
bool m_duplex = true;
bool m_tx = false;
bool m_dcd = false;
uint32_t m_sampleCount = 0U;
bool m_sampleInsert = false;
CDStarRX dstarRX;
CDStarTX dstarTX;
@ -35,11 +43,21 @@ CDMRIdleRX dmrIdleRX;
CDMRRX dmrRX;
CDMRTX dmrTX;
CDMRDMORX dmrDMORX;
CDMRDMOTX dmrDMOTX;
CYSFRX ysfRX;
CYSFTX ysfTX;
CCalRX calRX;
CCalTX calTX;
CP25RX p25RX;
CP25TX p25TX;
CCalDStarRX calDStarRX;
CCalDStarTX calDStarTX;
CCalDMR calDMR;
CCalRSSI calRSSI;
CCWIdTX cwIdTX;
CSerialPort serial;
CIO io;
@ -59,13 +77,26 @@ void loop()
if (m_dstarEnable && m_modemState == STATE_DSTAR)
dstarTX.process();
if (m_dmrEnable && m_modemState == STATE_DMR)
dmrTX.process();
if (m_dmrEnable && m_modemState == STATE_DMR) {
if (m_duplex)
dmrTX.process();
else
dmrDMOTX.process();
}
if (m_ysfEnable && m_modemState == STATE_YSF)
ysfTX.process();
if (m_modemState == STATE_CALIBRATE)
calTX.process();
if (m_p25Enable && m_modemState == STATE_P25)
p25TX.process();
if (m_modemState == STATE_DSTARCAL)
calDStarTX.process();
if (m_modemState == STATE_DMRCAL)
calDMR.process();
if (m_modemState == STATE_IDLE)
cwIdTX.process();
}

340
MMDVM_STM32F4xx.coproj Normal file
View File

@ -0,0 +1,340 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<Project version="2G - 1.7.8" name="MMDVM_STM32F4xx">
<Target name="MMDVM_Discovery_407" isCurrent="1">
<Device manufacturerId="9" manufacturerName="ST" chipId="344" chipName="STM32F407VG" boardId="" boardName=""/>
<BuildOption>
<Compile>
<Option name="OptimizationLevel" value="4"/>
<Option name="UseFPU" value="0"/>
<Option name="UserEditCompiler" value=""/>
<Option name="SupportCPlusplus" value="1"/>
<Option name="FPU" value="2"/>
<Includepaths>
<Includepath path="."/>
</Includepaths>
<DefinedSymbols>
<Define name="STM32F4XX"/>
<Define name="USE_STDPERIPH_DRIVER"/>
<Define name="__ASSEMBLY__"/>
<Define name="SUPPORT_CPLUSPLUS"/>
<Define name="STM32F40_41xxx"/>
<Define name="HSE_VALUE=8000000"/>
<Define name="STM32F4_DISCOVERY"/>
<Define name="__FPU_USED"/>
</DefinedSymbols>
</Compile>
<Link useDefault="0">
<Option name="DiscardUnusedSection" value="0"/>
<Option name="UserEditLinkder" value=""/>
<Option name="UseMemoryLayout" value="0"/>
<Option name="nostartfiles" value="1"/>
<Option name="LTO" value="0"/>
<Option name="IsNewStartupCode" value="1"/>
<Option name="Library" value="Semihosting"/>
<Option name="UserEditLinker" value="-lstdc++; --specs=nano.specs;"/>
<LinkedLibraries>
<Libset dir="stm32f4xx_lib\cmsis\lib\gcc\" libs="arm_cortexm4lf_math"/>
</LinkedLibraries>
<MemoryAreas debugInFlashNotRAM="1">
<Memory name="IROM1" type="ReadOnly" size="0x00100000" startValue="0x08000000"/>
<Memory name="IRAM1" type="ReadWrite" size="0x00020000" startValue="0x20000000"/>
<Memory name="IROM2" type="ReadOnly" size="" startValue=""/>
<Memory name="IRAM2" type="ReadWrite" size="0x00010000" startValue="0x10000000"/>
</MemoryAreas>
<LocateLinkFile path="./stm32f4xx_link.ld" type="0"/>
</Link>
<Output>
<Option name="OutputFileType" value="0"/>
<Option name="Path" value="./"/>
<Option name="Name" value="MMDVM_DIS"/>
<Option name="HEX" value="1"/>
<Option name="BIN" value="1"/>
</Output>
<User>
<UserRun name="Run#1" type="Before" checked="0" value=""/>
<UserRun name="Run#1" type="After" checked="0" value=""/>
</User>
</BuildOption>
<DebugOption>
<Option name="org.coocox.codebugger.gdbjtag.core.adapter" value="ST-Link"/>
<Option name="org.coocox.codebugger.gdbjtag.core.debugMode" value="SWD"/>
<Option name="org.coocox.codebugger.gdbjtag.core.clockDiv" value="1M"/>
<Option name="org.coocox.codebugger.gdbjtag.corerunToMain" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.jlinkgdbserver" value=""/>
<Option name="org.coocox.codebugger.gdbjtag.core.userDefineGDBScript" value=""/>
<Option name="org.coocox.codebugger.gdbjtag.core.targetEndianess" value="0"/>
<Option name="org.coocox.codebugger.gdbjtag.core.jlinkResetMode" value="Type 0: Normal"/>
<Option name="org.coocox.codebugger.gdbjtag.core.resetMode" value="SYSRESETREQ"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ifSemihost" value="0"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ifCacheRom" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ipAddress" value="127.0.0.1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.portNumber" value="2009"/>
<Option name="org.coocox.codebugger.gdbjtag.core.autoDownload" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.verify" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.downloadFuction" value="Erase Effected"/>
<Option name="org.coocox.codebugger.gdbjtag.core.defaultAlgorithm" value="STM32F4xx_1024.elf"/>
</DebugOption>
<ExcludeFile/>
</Target>
<Target name="MMDVM_Pi_446" isCurrent="0">
<Device manufacturerId="9" manufacturerName="ST" chipId="344" chipName="STM32F407VG" boardId="" boardName=""/>
<BuildOption>
<Compile>
<Option name="OptimizationLevel" value="4"/>
<Option name="UseFPU" value="0"/>
<Option name="UserEditCompiler" value=""/>
<Option name="SupportCPlusplus" value="1"/>
<Option name="FPU" value="2"/>
<Includepaths>
<Includepath path="."/>
</Includepaths>
<DefinedSymbols>
<Define name="STM32F4XX"/>
<Define name="USE_STDPERIPH_DRIVER"/>
<Define name="__ASSEMBLY__"/>
<Define name="SUPPORT_CPLUSPLUS"/>
<Define name="__FPU_USED"/>
<Define name="STM32F446xx"/>
<Define name="HSE_VALUE=12000000"/>
<Define name="STM32F4_PI"/>
<Define name="ARDUINO_MODE_PINS"/>
<Define name="SEND_RSSI_DATA"/>
<Define name="SERIAL_REPEATER"/>
</DefinedSymbols>
</Compile>
<Link useDefault="0">
<Option name="DiscardUnusedSection" value="0"/>
<Option name="UserEditLinkder" value=""/>
<Option name="UseMemoryLayout" value="0"/>
<Option name="nostartfiles" value="1"/>
<Option name="LTO" value="0"/>
<Option name="IsNewStartupCode" value="1"/>
<Option name="Library" value="Semihosting"/>
<Option name="UserEditLinker" value="-lstdc++; --specs=nano.specs;"/>
<LinkedLibraries>
<Libset dir="stm32f4xx_lib\cmsis\lib\gcc\" libs="arm_cortexm4lf_math"/>
</LinkedLibraries>
<MemoryAreas debugInFlashNotRAM="1">
<Memory name="IROM1" type="ReadOnly" size="0x00100000" startValue="0x08000000"/>
<Memory name="IRAM1" type="ReadWrite" size="0x00020000" startValue="0x20000000"/>
<Memory name="IROM2" type="ReadOnly" size="" startValue=""/>
<Memory name="IRAM2" type="ReadWrite" size="0x00010000" startValue="0x10000000"/>
</MemoryAreas>
<LocateLinkFile path="./stm32f4xx_link.ld" type="0"/>
</Link>
<Output>
<Option name="OutputFileType" value="0"/>
<Option name="Path" value="./"/>
<Option name="Name" value="MMDVM_PI"/>
<Option name="HEX" value="1"/>
<Option name="BIN" value="1"/>
</Output>
<User>
<UserRun name="Run#1" type="Before" checked="0" value=""/>
<UserRun name="Run#1" type="After" checked="0" value=""/>
</User>
</BuildOption>
<DebugOption>
<Option name="org.coocox.codebugger.gdbjtag.core.adapter" value="ST-Link"/>
<Option name="org.coocox.codebugger.gdbjtag.core.debugMode" value="SWD"/>
<Option name="org.coocox.codebugger.gdbjtag.core.clockDiv" value="1M"/>
<Option name="org.coocox.codebugger.gdbjtag.corerunToMain" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.jlinkgdbserver" value=""/>
<Option name="org.coocox.codebugger.gdbjtag.core.userDefineGDBScript" value=""/>
<Option name="org.coocox.codebugger.gdbjtag.core.targetEndianess" value="0"/>
<Option name="org.coocox.codebugger.gdbjtag.core.jlinkResetMode" value="Type 0: Normal"/>
<Option name="org.coocox.codebugger.gdbjtag.core.resetMode" value="SYSRESETREQ"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ifSemihost" value="0"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ifCacheRom" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ipAddress" value="127.0.0.1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.portNumber" value="2009"/>
<Option name="org.coocox.codebugger.gdbjtag.core.autoDownload" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.verify" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.downloadFuction" value="Erase Effected"/>
<Option name="org.coocox.codebugger.gdbjtag.core.defaultAlgorithm" value="STM32F4xx_1024.elf"/>
</DebugOption>
<ExcludeFile/>
</Target>
<Target name="MMDVM_Nucleo_446" isCurrent="0">
<Device manufacturerId="9" manufacturerName="ST" chipId="344" chipName="STM32F407VG" boardId="" boardName=""/>
<BuildOption>
<Compile>
<Option name="OptimizationLevel" value="4"/>
<Option name="UseFPU" value="0"/>
<Option name="UserEditCompiler" value=""/>
<Option name="SupportCPlusplus" value="1"/>
<Option name="FPU" value="2"/>
<Includepaths>
<Includepath path="."/>
</Includepaths>
<DefinedSymbols>
<Define name="STM32F4XX"/>
<Define name="USE_STDPERIPH_DRIVER"/>
<Define name="__ASSEMBLY__"/>
<Define name="SUPPORT_CPLUSPLUS"/>
<Define name="HSE_VALUE=8000000"/>
<Define name="__FPU_USED"/>
<Define name="STM32F4_NUCLEO"/>
<Define name="STM32F446xx"/>
</DefinedSymbols>
</Compile>
<Link useDefault="0">
<Option name="DiscardUnusedSection" value="0"/>
<Option name="UserEditLinkder" value=""/>
<Option name="UseMemoryLayout" value="0"/>
<Option name="nostartfiles" value="1"/>
<Option name="LTO" value="0"/>
<Option name="IsNewStartupCode" value="1"/>
<Option name="Library" value="Semihosting"/>
<Option name="UserEditLinker" value="-lstdc++; --specs=nano.specs;"/>
<LinkedLibraries>
<Libset dir="stm32f4xx_lib\cmsis\lib\gcc\" libs="arm_cortexm4lf_math"/>
</LinkedLibraries>
<MemoryAreas debugInFlashNotRAM="1">
<Memory name="IROM1" type="ReadOnly" size="0x00100000" startValue="0x08000000"/>
<Memory name="IRAM1" type="ReadWrite" size="0x00020000" startValue="0x20000000"/>
<Memory name="IROM2" type="ReadOnly" size="" startValue=""/>
<Memory name="IRAM2" type="ReadWrite" size="0x00010000" startValue="0x10000000"/>
</MemoryAreas>
<LocateLinkFile path="./stm32f4xx_link.ld" type="0"/>
</Link>
<Output>
<Option name="OutputFileType" value="0"/>
<Option name="Path" value="./"/>
<Option name="Name" value="MMDVM_NUCLEO"/>
<Option name="HEX" value="1"/>
<Option name="BIN" value="1"/>
</Output>
<User>
<UserRun name="Run#1" type="Before" checked="0" value=""/>
<UserRun name="Run#1" type="After" checked="0" value=""/>
</User>
</BuildOption>
<DebugOption>
<Option name="org.coocox.codebugger.gdbjtag.core.adapter" value="ST-Link"/>
<Option name="org.coocox.codebugger.gdbjtag.core.debugMode" value="SWD"/>
<Option name="org.coocox.codebugger.gdbjtag.core.clockDiv" value="1M"/>
<Option name="org.coocox.codebugger.gdbjtag.corerunToMain" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.jlinkgdbserver" value=""/>
<Option name="org.coocox.codebugger.gdbjtag.core.userDefineGDBScript" value=""/>
<Option name="org.coocox.codebugger.gdbjtag.core.targetEndianess" value="0"/>
<Option name="org.coocox.codebugger.gdbjtag.core.jlinkResetMode" value="Type 0: Normal"/>
<Option name="org.coocox.codebugger.gdbjtag.core.resetMode" value="SYSRESETREQ"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ifSemihost" value="0"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ifCacheRom" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.ipAddress" value="127.0.0.1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.portNumber" value="2009"/>
<Option name="org.coocox.codebugger.gdbjtag.core.autoDownload" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.verify" value="1"/>
<Option name="org.coocox.codebugger.gdbjtag.core.downloadFuction" value="Erase Effected"/>
<Option name="org.coocox.codebugger.gdbjtag.core.defaultAlgorithm" value="STM32F4xx_1024.elf"/>
</DebugOption>
<ExcludeFile/>
</Target>
<Components path="./">
</Components>
<Files>
<File name="DMRIdleRX.h" path="DMRIdleRX.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_dac.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_dac.c" type="1"/>
<File name="DMRDMOTX.cpp" path="DMRDMOTX.cpp" type="1"/>
<File name="DMRRX.cpp" path="DMRRX.cpp" type="1"/>
<File name="YSFRX.cpp" path="YSFRX.cpp" type="1"/>
<File name="CalRSSI.cpp" path="CalRSSI.cpp" type="1"/>
<File name="STM32F4XX_Lib/Device/stm32f4xx.h" path="STM32F4XX_Lib/Device/stm32f4xx.h" type="1"/>
<File name="SampleRB.cpp" path="SampleRB.cpp" type="1"/>
<File name="CalDStarTX.h" path="CalDStarTX.h" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Include/core_cm4.h" path="STM32F4XX_Lib/CMSIS/Include/core_cm4.h" type="1"/>
<File name="DMRSlotRX.h" path="DMRSlotRX.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_tim.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_tim.c" type="1"/>
<File name="YSFRX.h" path="YSFRX.h" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Include" path="" type="2"/>
<File name="IO.cpp" path="IO.cpp" type="1"/>
<File name="DMRDMORX.cpp" path="DMRDMORX.cpp" type="1"/>
<File name="P25RX.h" path="P25RX.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/misc.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/misc.c" type="1"/>
<File name="STM32F4XX_Lib/CMSIS" path="" type="2"/>
<File name="SerialArduino.cpp" path="SerialArduino.cpp" type="1"/>
<File name="SerialPort.cpp" path="SerialPort.cpp" type="1"/>
<File name="STM32F4XX_Lib/Device/stm32f4xx_conf.h" path="STM32F4XX_Lib/Device/stm32f4xx_conf.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_adc.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_adc.c" type="1"/>
<File name="DStarTX.cpp" path="DStarTX.cpp" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_usart.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_usart.c" type="1"/>
<File name="SampleRB.h" path="SampleRB.h" type="1"/>
<File name="YSFTX.h" path="YSFTX.h" type="1"/>
<File name="DMRRX.h" path="DMRRX.h" type="1"/>
<File name="CalRSSI.h" path="CalRSSI.h" type="1"/>
<File name="IOTeensy.cpp" path="IOTeensy.cpp" type="1"/>
<File name="MMDVM.cpp" path="MMDVM.cpp" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Include/core_cmSimd.h" path="STM32F4XX_Lib/CMSIS/Include/core_cmSimd.h" type="1"/>
<File name="DMRDMORX.h" path="DMRDMORX.h" type="1"/>
<File name="SerialPort.h" path="SerialPort.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_dac.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_dac.h" type="1"/>
<File name="CWIdTX.h" path="CWIdTX.h" type="1"/>
<File name="STM32F4XX_Lib/Device/system_stm32f4xx.h" path="STM32F4XX_Lib/Device/system_stm32f4xx.h" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Include/core_cmFunc.h" path="STM32F4XX_Lib/CMSIS/Include/core_cmFunc.h" type="1"/>
<File name="CalDStarTX.cpp" path="CalDStarTX.cpp" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source" path="" type="2"/>
<File name="CalDMR.h" path="CalDMR.h" type="1"/>
<File name="DMRDMOTX.h" path="DMRDMOTX.h" type="1"/>
<File name="IODue.cpp" path="IODue.cpp" type="1"/>
<File name="DMRTX.cpp" path="DMRTX.cpp" type="1"/>
<File name="P25RX.cpp" path="P25RX.cpp" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Lib/GCC" path="" type="2"/>
<File name="STM32F4XX_Lib" path="" type="2"/>
<File name="STM32F4XX_Lib/CMSIS/Include/core_cmInstr.h" path="STM32F4XX_Lib/CMSIS/Include/core_cmInstr.h" type="1"/>
<File name="DMRTX.h" path="DMRTX.h" type="1"/>
<File name="STM32F4XX_Lib/Device/system_stm32f4xx.c" path="STM32F4XX_Lib/Device/system_stm32f4xx.c" type="1"/>
<File name="RSSIRB.h" path="RSSIRB.h" type="1"/>
<File name="STM32F4XX_Lib/Device/startup/startup_stm32f4xx.c" path="STM32F4XX_Lib/Device/startup/startup_stm32f4xx.c" type="1"/>
<File name="STM32F4XX_Lib/Device/startup" path="" type="2"/>
<File name="SerialRB.h" path="SerialRB.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_gpio.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_gpio.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver" path="" type="2"/>
<File name="DMRDefines.h" path="DMRDefines.h" type="1"/>
<File name="CalDMR.cpp" path="CalDMR.cpp" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_adc.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_adc.h" type="1"/>
<File name="SerialSTM.cpp" path="SerialSTM.cpp" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Lib/GCC/libarm_cortexM4lf_math.a" path="STM32F4XX_Lib/CMSIS/Lib/GCC/libarm_cortexM4lf_math.a" type="1"/>
<File name="DStarDefines.h" path="DStarDefines.h" type="1"/>
<File name="DStarRX.h" path="DStarRX.h" type="1"/>
<File name="Config.h" path="Config.h" type="1"/>
<File name="DMRSlotType.cpp" path="DMRSlotType.cpp" type="1"/>
<File name="Globals.h" path="Globals.h" type="1"/>
<File name="STM32F4XX_Lib/Device" path="" type="2"/>
<File name="CalDStarRX.cpp" path="CalDStarRX.cpp" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_tim.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_tim.h" type="1"/>
<File name="CalDStarRX.h" path="CalDStarRX.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include" path="" type="2"/>
<File name="IO.h" path="IO.h" type="1"/>
<File name="Utils.cpp" path="Utils.cpp" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/.DS_Store" path="STM32F4XX_Lib/CMSIS/.DS_Store" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Lib/.DS_Store" path="STM32F4XX_Lib/CMSIS/Lib/.DS_Store" type="1"/>
<File name="Utils.h" path="Utils.h" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Lib" path="" type="2"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/.DS_Store" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/.DS_Store" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Include/.DS_Store" path="STM32F4XX_Lib/CMSIS/Include/.DS_Store" type="1"/>
<File name="STM32F4XX_Lib/CMSIS/Include/arm_math.h" path="STM32F4XX_Lib/CMSIS/Include/arm_math.h" type="1"/>
<File name="YSFDefines.h" path="YSFDefines.h" type="1"/>
<File name="DStarTX.h" path="DStarTX.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_rcc.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_rcc.c" type="1"/>
<File name="STM32F4XX_Lib/Device/.DS_Store" path="STM32F4XX_Lib/Device/.DS_Store" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_rcc.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_rcc.h" type="1"/>
<File name="P25Defines.h" path="P25Defines.h" type="1"/>
<File name="DMRSlotType.h" path="DMRSlotType.h" type="1"/>
<File name="Debug.h" path="Debug.h" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/misc.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/misc.h" type="1"/>
<File name="P25TX.h" path="P25TX.h" type="1"/>
<File name="RSSIRB.cpp" path="RSSIRB.cpp" type="1"/>
<File name="DStarRX.cpp" path="DStarRX.cpp" type="1"/>
<File name="DMRSlotRX.cpp" path="DMRSlotRX.cpp" type="1"/>
<File name="IOSTM.cpp" path="IOSTM.cpp" type="1"/>
<File name="P25TX.cpp" path="P25TX.cpp" type="1"/>
<File name="SerialRB.cpp" path="SerialRB.cpp" type="1"/>
<File name="CWIdTX.cpp" path="CWIdTX.cpp" type="1"/>
<File name="DMRIdleRX.cpp" path="DMRIdleRX.cpp" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_usart.h" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/stm32f4xx_usart.h" type="1"/>
<File name="STM32F4XX_Lib/.DS_Store" path="STM32F4XX_Lib/.DS_Store" type="1"/>
<File name="YSFTX.cpp" path="YSFTX.cpp" type="1"/>
<File name="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_gpio.c" path="STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/source/stm32f4xx_gpio.c" type="1"/>
</Files>
</Project>

173
Makefile Normal file
View File

@ -0,0 +1,173 @@
# Copyright (C) 2016 by Andy Uribe CA6JAU
# Copyright (C) 2016 by Jim McLaughlin KI6ZUM
# 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.
# GNU ARM Embedded Toolchain
CC=arm-none-eabi-gcc
CXX=arm-none-eabi-g++
LD=arm-none-eabi-ld
AR=arm-none-eabi-ar
AS=arm-none-eabi-as
CP=arm-none-eabi-objcopy
OD=arm-none-eabi-objdump
NM=arm-none-eabi-nm
SIZE=arm-none-eabi-size
A2L=arm-none-eabi-addr2line
# Directory Structure
BINDIR=bin
# Find source files
# "SystemRoot" is only defined in Windows
ifdef SYSTEMROOT
ASOURCES=$(shell dir /S /B *.s)
CSOURCES=$(shell dir /S /B *.c)
CXXSOURCES=$(shell dir /S /B *.cpp)
CLEANCMD=del /S *.o *.hex *.bin *.elf
MDBIN=md $@
else ifdef SystemRoot
ASOURCES=$(shell dir /S /B *.s)
CSOURCES=$(shell dir /S /B *.c)
CXXSOURCES=$(shell dir /S /B *.cpp)
CLEANCMD=del /S *.o *.hex *.bin *.elf
MDBIN=md $@
else
ASOURCES=$(shell find . -name '*.s')
CSOURCES=$(shell find . -name '*.c')
CXXSOURCES=$(shell find . -name '*.cpp')
CLEANCMD=rm -f $(OBJECTS) $(BINDIR)/$(BINELF) $(BINDIR)/$(BINHEX) $(BINDIR)/$(BINBIN)
MDBIN=mkdir $@
endif
# Default reference oscillator frequencies
ifndef $(OSC)
ifeq ($(MAKECMDGOALS),pi)
OSC=12000000
else
OSC=8000000
endif
endif
# Find header directories
INC= . STM32F4XX_Lib/CMSIS/Include/ STM32F4XX_Lib/Device/ STM32F4XX_Lib/STM32F4xx_StdPeriph_Driver/include/
INCLUDES=$(INC:%=-I%)
# Find libraries
INCLUDES_LIBS=STM32F4XX_Lib/CMSIS/Lib/GCC/libarm_cortexM4lf_math.a
LINK_LIBS=
# Create object list
OBJECTS=$(ASOURCES:%.s=%.o)
OBJECTS+=$(CSOURCES:%.c=%.o)
OBJECTS+=$(CXXSOURCES:%.cpp=%.o)
# Define output files ELF & IHEX
BINELF=outp.elf
BINHEX=outp.hex
BINBIN=outp.bin
# MCU FLAGS
MCFLAGS=-mcpu=cortex-m4 -mthumb -mlittle-endian \
-mfpu=fpv4-sp-d16 -mfloat-abi=hard -mthumb-interwork
# COMPILE FLAGS
# STM32F4 Discovery board:
DEFS_DIS=-DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F40_41xxx -DSTM32F4_DISCOVERY -DHSE_VALUE=$(OSC)
# Pi board:
DEFS_PI=-DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F446xx -DSTM32F4_PI -DARDUINO_MODE_PINS -DSEND_RSSI_DATA -DSERIAL_REPEATER -DHSE_VALUE=$(OSC)
# STM32F4 Nucleo 446 board:
DEFS_NUCLEO=-DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F446xx -DSTM32F4_NUCLEO -DHSE_VALUE=$(OSC)
CFLAGS=-c $(MCFLAGS) $(INCLUDES)
CXXFLAGS=-c $(MCFLAGS) $(INCLUDES)
# LINKER FLAGS
LDSCRIPT=stm32f4xx_link.ld
LDFLAGS =-T $(LDSCRIPT) $(MCFLAGS) --specs=nosys.specs $(INCLUDES_LIBS) $(LINK_LIBS)
# Build Rules
.PHONY: all release dis pi nucleo debug clean
# Default target: STM32F4 Discovery board
all: dis
pi: CFLAGS+=$(DEFS_PI) -Os -ffunction-sections -fdata-sections -fno-builtin -Wno-implicit -DCUSTOM_NEW -DNO_EXCEPTIONS
pi: CXXFLAGS+=$(DEFS_PI) -Os -fno-exceptions -ffunction-sections -fdata-sections -fno-builtin -fno-rtti -DCUSTOM_NEW -DNO_EXCEPTIONS
pi: LDFLAGS+=-Os --specs=nano.specs
pi: release
nucleo: CFLAGS+=$(DEFS_NUCLEO) -Os -ffunction-sections -fdata-sections -fno-builtin -Wno-implicit -DCUSTOM_NEW -DNO_EXCEPTIONS
nucleo: CXXFLAGS+=$(DEFS_NUCLEO) -Os -fno-exceptions -ffunction-sections -fdata-sections -fno-builtin -fno-rtti -DCUSTOM_NEW -DNO_EXCEPTIONS
nucleo: LDFLAGS+=-Os --specs=nano.specs
nucleo: release
dis: CFLAGS+=$(DEFS_DIS) -Os -ffunction-sections -fdata-sections -fno-builtin -Wno-implicit -DCUSTOM_NEW -DNO_EXCEPTIONS
dis: CXXFLAGS+=$(DEFS_DIS) -Os -fno-exceptions -ffunction-sections -fdata-sections -fno-builtin -fno-rtti -DCUSTOM_NEW -DNO_EXCEPTIONS
dis: LDFLAGS+=-Os --specs=nano.specs
dis: release
debug: CFLAGS+=-g
debug: CXXFLAGS+=-g
debug: LDFLAGS+=-g
debug: release
release: $(BINDIR)
release: $(BINDIR)/$(BINHEX)
release: $(BINDIR)/$(BINBIN)
$(BINDIR):
$(MDBIN)
$(BINDIR)/$(BINHEX): $(BINDIR)/$(BINELF)
$(CP) -O ihex $< $@
@echo "Objcopy from ELF to IHEX complete!\n"
$(BINDIR)/$(BINBIN): $(BINDIR)/$(BINELF)
$(CP) -O binary $< $@
@echo "Objcopy from ELF to BINARY complete!\n"
$(BINDIR)/$(BINELF): $(OBJECTS)
$(CXX) $(OBJECTS) $(LDFLAGS) -o $@
@echo "Linking complete!\n"
$(SIZE) $(BINDIR)/$(BINELF)
%.o: %.cpp
$(CXX) $(CXXFLAGS) $< -o $@
@echo "Compiled "$<"!\n"
%.o: %.c
$(CC) $(CFLAGS) $< -o $@
@echo "Compiled "$<"!\n"
%.o: %.s
$(CC) $(CFLAGS) $< -o $@
@echo "Assambled "$<"!\n"
clean:
$(CLEANCMD)
deploy:
ifneq ($(wildcard /usr/bin/openocd),)
/usr/bin/openocd -f /usr/share/openocd/scripts/board/stm32f4discovery.cfg -c "program bin/$(BINELF) verify reset exit"
endif
ifneq ($(wildcard /usr/local/bin/openocd),)
/usr/local/bin/openocd -f /usr/local/share/openocd/scripts/board/stm32f4discovery.cfg -c "program bin/$(BINELF) verify reset exit"
endif
ifneq ($(wildcard /opt/openocd/bin/openocd),)
/opt/openocd/bin/openocd -f /opt/openocd/share/openocd/scripts/board/stm32f4discovery.cfg -c "program bin/$(BINELF) verify reset exit"
endif

69
P25Defines.h Normal file
View File

@ -0,0 +1,69 @@
/*
* Copyright (C) 2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(P25DEFINES_H)
#define P25DEFINES_H
const unsigned int P25_RADIO_SYMBOL_LENGTH = 5U; // At 24 kHz sample rate
const unsigned int P25_HDR_FRAME_LENGTH_BYTES = 99U;
const unsigned int P25_HDR_FRAME_LENGTH_BITS = P25_HDR_FRAME_LENGTH_BYTES * 8U;
const unsigned int P25_HDR_FRAME_LENGTH_SYMBOLS = P25_HDR_FRAME_LENGTH_BYTES * 4U;
const unsigned int P25_HDR_FRAME_LENGTH_SAMPLES = P25_HDR_FRAME_LENGTH_SYMBOLS * P25_RADIO_SYMBOL_LENGTH;
const unsigned int P25_LDU_FRAME_LENGTH_BYTES = 216U;
const unsigned int P25_LDU_FRAME_LENGTH_BITS = P25_LDU_FRAME_LENGTH_BYTES * 8U;
const unsigned int P25_LDU_FRAME_LENGTH_SYMBOLS = P25_LDU_FRAME_LENGTH_BYTES * 4U;
const unsigned int P25_LDU_FRAME_LENGTH_SAMPLES = P25_LDU_FRAME_LENGTH_SYMBOLS * P25_RADIO_SYMBOL_LENGTH;
const unsigned int P25_TERMLC_FRAME_LENGTH_BYTES = 54U;
const unsigned int P25_TERMLC_FRAME_LENGTH_BITS = P25_TERMLC_FRAME_LENGTH_BYTES * 8U;
const unsigned int P25_TERMLC_FRAME_LENGTH_SYMBOLS = P25_TERMLC_FRAME_LENGTH_BYTES * 4U;
const unsigned int P25_TERMLC_FRAME_LENGTH_SAMPLES = P25_TERMLC_FRAME_LENGTH_SYMBOLS * P25_RADIO_SYMBOL_LENGTH;
const unsigned int P25_TERM_FRAME_LENGTH_BYTES = 18U;
const unsigned int P25_TERM_FRAME_LENGTH_BITS = P25_TERM_FRAME_LENGTH_BYTES * 8U;
const unsigned int P25_TERM_FRAME_LENGTH_SYMBOLS = P25_TERM_FRAME_LENGTH_BYTES * 4U;
const unsigned int P25_TERM_FRAME_LENGTH_SAMPLES = P25_TERM_FRAME_LENGTH_SYMBOLS * P25_RADIO_SYMBOL_LENGTH;
const unsigned int P25_SYNC_LENGTH_BYTES = 6U;
const unsigned int P25_SYNC_LENGTH_BITS = P25_SYNC_LENGTH_BYTES * 8U;
const unsigned int P25_SYNC_LENGTH_SYMBOLS = P25_SYNC_LENGTH_BYTES * 4U;
const unsigned int P25_SYNC_LENGTH_SAMPLES = P25_SYNC_LENGTH_SYMBOLS * P25_RADIO_SYMBOL_LENGTH;
const unsigned int P25_NID_LENGTH_BITS = 64U;
const unsigned int P25_NID_LENGTH_SYMBOLS = 32U;
const unsigned int P25_NID_LENGTH_SAMPLESS = P25_NID_LENGTH_SYMBOLS * P25_RADIO_SYMBOL_LENGTH;
const uint8_t P25_SYNC_BYTES[] = {0x55U, 0x75U, 0xF5U, 0xFFU, 0x77U, 0xFFU};
const uint8_t P25_SYNC_BYTES_LENGTH = 6U;
const uint64_t P25_SYNC_BITS = 0x00005575F5FF77FFU;
const uint64_t P25_SYNC_BITS_MASK = 0x0000FFFFFFFFFFFFU;
// 5 5 7 5 F 5 F F 7 7 F F
// 01 01 01 01 01 11 01 01 11 11 01 01 11 11 11 11 01 11 01 11 11 11 11 11
// +3 +3 +3 +3 +3 -3 +3 +3 -3 -3 +3 +3 -3 -3 -3 -3 +3 -3 +3 -3 -3 -3 -3 -3
const int8_t P25_SYNC_SYMBOLS_VALUES[] = {+3, +3, +3, +3, +3, -3, +3, +3, -3, -3, +3, +3, -3, -3, -3, -3, +3, -3, +3, -3, -3, -3, -3, -3};
const uint32_t P25_SYNC_SYMBOLS = 0x00FB30A0U;
const uint32_t P25_SYNC_SYMBOLS_MASK = 0x00FFFFFFU;
#endif

490
P25RX.cpp Normal file
View File

@ -0,0 +1,490 @@
/*
* Copyright (C) 2009-2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#define WANT_DEBUG
// #define DUMP_SAMPLES
#include "Config.h"
#include "Globals.h"
#include "P25RX.h"
#include "Utils.h"
const q15_t SCALING_FACTOR = 18750; // Q15(0.57)
const uint8_t MAX_SYNC_BIT_START_ERRS = 2U;
const uint8_t MAX_SYNC_BIT_RUN_ERRS = 4U;
const uint8_t MAX_SYNC_SYMBOLS_ERRS = 2U;
const uint8_t BIT_MASK_TABLE[] = { 0x80U, 0x40U, 0x20U, 0x10U, 0x08U, 0x04U, 0x02U, 0x01U };
#define WRITE_BIT1(p,i,b) p[(i)>>3] = (b) ? (p[(i)>>3] | BIT_MASK_TABLE[(i)&7]) : (p[(i)>>3] & ~BIT_MASK_TABLE[(i)&7])
const uint8_t NOAVEPTR = 99U;
const uint16_t NOENDPTR = 9999U;
const unsigned int MAX_SYNC_FRAMES = 4U + 1U;
CP25RX::CP25RX() :
m_state(P25RXS_NONE),
m_bitBuffer(),
m_buffer(),
m_bitPtr(0U),
m_dataPtr(0U),
m_hdrStartPtr(NOENDPTR),
m_lduStartPtr(NOENDPTR),
m_lduEndPtr(NOENDPTR),
m_minSyncPtr(NOENDPTR),
m_maxSyncPtr(NOENDPTR),
m_hdrSyncPtr(NOENDPTR),
m_lduSyncPtr(NOENDPTR),
m_maxCorr(0),
m_lostCount(0U),
m_countdown(0U),
m_centre(),
m_centreVal(0),
m_threshold(),
m_thresholdVal(0),
m_averagePtr(NOAVEPTR),
m_rssiAccum(0U),
m_rssiCount(0U)
{
}
void CP25RX::reset()
{
m_state = P25RXS_NONE;
m_dataPtr = 0U;
m_bitPtr = 0U;
m_maxCorr = 0;
m_averagePtr = NOAVEPTR;
m_hdrStartPtr = NOENDPTR;
m_lduStartPtr = NOENDPTR;
m_lduEndPtr = NOENDPTR;
m_hdrSyncPtr = NOENDPTR;
m_lduSyncPtr = NOENDPTR;
m_minSyncPtr = NOENDPTR;
m_maxSyncPtr = NOENDPTR;
m_centreVal = 0;
m_thresholdVal = 0;
m_lostCount = 0U;
m_countdown = 0U;
m_rssiAccum = 0U;
m_rssiCount = 0U;
}
void CP25RX::samples(const q15_t* samples, uint16_t* rssi, uint8_t length)
{
for (uint8_t i = 0U; i < length; i++) {
q15_t sample = samples[i];
m_rssiAccum += rssi[i];
m_rssiCount++;
m_bitBuffer[m_bitPtr] <<= 1;
if (sample < 0)
m_bitBuffer[m_bitPtr] |= 0x01U;
m_buffer[m_dataPtr] = sample;
switch (m_state) {
case P25RXS_HDR:
processHdr(sample);
break;
case P25RXS_LDU:
processLdu(sample);
break;
default:
processNone(sample);
break;
}
m_dataPtr++;
if (m_dataPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_dataPtr = 0U;
m_bitPtr++;
if (m_bitPtr >= P25_RADIO_SYMBOL_LENGTH)
m_bitPtr = 0U;
}
}
void CP25RX::processNone(q15_t sample)
{
bool ret = correlateSync();
if (ret) {
// On the first sync, start the countdown to the state change
if (m_countdown == 0U) {
m_rssiAccum = 0U;
m_rssiCount = 0U;
io.setDecode(true);
io.setADCDetection(true);
m_averagePtr = NOAVEPTR;
m_countdown = 5U;
}
}
if (m_countdown > 0U)
m_countdown--;
if (m_countdown == 1U) {
// These are the sync positions for the following LDU after a HDR
m_minSyncPtr = m_hdrSyncPtr + P25_HDR_FRAME_LENGTH_SAMPLES - 1U;
if (m_minSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_minSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
m_maxSyncPtr = m_hdrSyncPtr + P25_HDR_FRAME_LENGTH_SAMPLES + 1U;
if (m_maxSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_maxSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
m_state = P25RXS_HDR;
m_countdown = 0U;
}
}
void CP25RX::processHdr(q15_t sample)
{
if (m_minSyncPtr < m_maxSyncPtr) {
if (m_dataPtr >= m_minSyncPtr && m_dataPtr <= m_maxSyncPtr)
correlateSync();
} else {
if (m_dataPtr >= m_minSyncPtr || m_dataPtr <= m_maxSyncPtr)
correlateSync();
}
if (m_dataPtr == m_maxSyncPtr) {
if (m_hdrSyncPtr != m_lduSyncPtr) {
calculateLevels(m_hdrStartPtr, P25_HDR_FRAME_LENGTH_SYMBOLS);
DEBUG4("P25RX: sync found in Hdr pos/centre/threshold", m_hdrSyncPtr, m_centreVal, m_thresholdVal);
uint8_t frame[P25_HDR_FRAME_LENGTH_BYTES + 1U];
samplesToBits(m_hdrStartPtr, P25_HDR_FRAME_LENGTH_SYMBOLS, frame, 8U, m_centreVal, m_thresholdVal);
frame[0U] = 0x01U;
serial.writeP25Hdr(frame, P25_HDR_FRAME_LENGTH_BYTES + 1U);
}
m_minSyncPtr = m_lduSyncPtr + P25_LDU_FRAME_LENGTH_SAMPLES - 1U;
if (m_minSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_minSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
m_maxSyncPtr = m_lduSyncPtr + 1U;
if (m_maxSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_maxSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
m_state = P25RXS_LDU;
m_maxCorr = 0;
}
}
void CP25RX::processLdu(q15_t sample)
{
if (m_minSyncPtr < m_maxSyncPtr) {
if (m_dataPtr >= m_minSyncPtr && m_dataPtr <= m_maxSyncPtr)
correlateSync();
} else {
if (m_dataPtr >= m_minSyncPtr || m_dataPtr <= m_maxSyncPtr)
correlateSync();
}
if (m_dataPtr == m_lduEndPtr) {
// Only update the centre and threshold if they are from a good sync
if (m_lostCount == MAX_SYNC_FRAMES) {
m_minSyncPtr = m_lduSyncPtr + P25_LDU_FRAME_LENGTH_SAMPLES - 1U;
if (m_minSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_minSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
m_maxSyncPtr = m_lduSyncPtr + 1U;
if (m_maxSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_maxSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
}
calculateLevels(m_lduStartPtr, P25_LDU_FRAME_LENGTH_SYMBOLS);
DEBUG4("P25RX: sync found in Ldu pos/centre/threshold", m_lduSyncPtr, m_centreVal, m_thresholdVal);
uint8_t frame[P25_LDU_FRAME_LENGTH_BYTES + 3U];
samplesToBits(m_lduStartPtr, P25_LDU_FRAME_LENGTH_SYMBOLS, frame, 8U, m_centreVal, m_thresholdVal);
// We've not seen a data sync for too long, signal RXLOST and change to RX_NONE
m_lostCount--;
if (m_lostCount == 0U) {
DEBUG1("P25RX: sync timed out, lost lock");
io.setDecode(false);
io.setADCDetection(false);
serial.writeP25Lost();
m_state = P25RXS_NONE;
m_lduEndPtr = NOENDPTR;
m_averagePtr = NOAVEPTR;
m_countdown = 0U;
m_maxCorr = 0;
} else {
frame[0U] = m_lostCount == (MAX_SYNC_FRAMES - 1U) ? 0x01U : 0x00U;
writeRSSILdu(frame);
#if defined(DUMP_SAMPLES)
writeSamples(m_lduStartPtr, frame[0U]);
#endif
m_maxCorr = 0;
}
}
}
bool CP25RX::correlateSync()
{
if (countBits32((m_bitBuffer[m_bitPtr] & P25_SYNC_SYMBOLS_MASK) ^ P25_SYNC_SYMBOLS) <= MAX_SYNC_SYMBOLS_ERRS) {
uint16_t ptr = m_dataPtr + P25_LDU_FRAME_LENGTH_SAMPLES - P25_SYNC_LENGTH_SAMPLES + P25_RADIO_SYMBOL_LENGTH;
if (ptr >= P25_LDU_FRAME_LENGTH_SAMPLES)
ptr -= P25_LDU_FRAME_LENGTH_SAMPLES;
q31_t corr = 0;
q15_t min = 16000;
q15_t max = -16000;
for (uint8_t i = 0U; i < P25_SYNC_LENGTH_SYMBOLS; i++) {
q15_t val = m_buffer[ptr];
if (val > max)
max = val;
if (val < min)
min = val;
switch (P25_SYNC_SYMBOLS_VALUES[i]) {
case +3:
corr -= (val + val + val);
break;
case +1:
corr -= val;
break;
case -1:
corr += val;
break;
default: // -3
corr += (val + val + val);
break;
}
ptr += P25_RADIO_SYMBOL_LENGTH;
if (ptr >= P25_LDU_FRAME_LENGTH_SAMPLES)
ptr -= P25_LDU_FRAME_LENGTH_SAMPLES;
}
if (corr > m_maxCorr) {
if (m_averagePtr == NOAVEPTR) {
m_centreVal = (max + min) >> 1;
q31_t v1 = (max - m_centreVal) * SCALING_FACTOR;
m_thresholdVal = q15_t(v1 >> 15);
}
uint16_t startPtr = m_dataPtr + P25_LDU_FRAME_LENGTH_SAMPLES - P25_SYNC_LENGTH_SAMPLES + P25_RADIO_SYMBOL_LENGTH;
if (startPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
startPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
uint8_t sync[P25_SYNC_BYTES_LENGTH];
samplesToBits(startPtr, P25_SYNC_LENGTH_SYMBOLS, sync, 0U, m_centreVal, m_thresholdVal);
uint8_t maxErrs;
if (m_state == P25RXS_NONE)
maxErrs = MAX_SYNC_BIT_START_ERRS;
else
maxErrs = MAX_SYNC_BIT_RUN_ERRS;
uint8_t errs = 0U;
for (uint8_t i = 0U; i < P25_SYNC_BYTES_LENGTH; i++)
errs += countBits8(sync[i] ^ P25_SYNC_BYTES[i]);
if (errs <= maxErrs) {
m_maxCorr = corr;
m_lostCount = MAX_SYNC_FRAMES;
m_lduSyncPtr = m_dataPtr;
// These are the positions of the start and end of an LDU
m_lduStartPtr = startPtr;
m_lduEndPtr = m_dataPtr + P25_LDU_FRAME_LENGTH_SAMPLES - P25_SYNC_LENGTH_SAMPLES - 1U;
if (m_lduEndPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_lduEndPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
if (m_state == P25RXS_NONE) {
m_hdrSyncPtr = m_dataPtr;
// This is the position of the start of a HDR
m_hdrStartPtr = startPtr;
// These are the range of positions for a sync for an LDU following a HDR
m_minSyncPtr = m_dataPtr + P25_HDR_FRAME_LENGTH_SAMPLES - 1U;
if (m_minSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_minSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
m_maxSyncPtr = m_dataPtr + P25_HDR_FRAME_LENGTH_SAMPLES + 1U;
if (m_maxSyncPtr >= P25_LDU_FRAME_LENGTH_SAMPLES)
m_maxSyncPtr -= P25_LDU_FRAME_LENGTH_SAMPLES;
}
return true;
}
}
}
return false;
}
void CP25RX::calculateLevels(uint16_t start, uint16_t count)
{
q15_t maxPos = -16000;
q15_t minPos = 16000;
q15_t maxNeg = 16000;
q15_t minNeg = -16000;
for (uint16_t i = 0U; i < count; i++) {
q15_t sample = m_buffer[start];
if (sample > 0) {
if (sample > maxPos)
maxPos = sample;
if (sample < minPos)
minPos = sample;
} else {
if (sample < maxNeg)
maxNeg = sample;
if (sample > minNeg)
minNeg = sample;
}
start += P25_RADIO_SYMBOL_LENGTH;
if (start >= P25_LDU_FRAME_LENGTH_SAMPLES)
start -= P25_LDU_FRAME_LENGTH_SAMPLES;
}
q15_t posThresh = (maxPos + minPos) >> 1;
q15_t negThresh = (maxNeg + minNeg) >> 1;
q15_t centre = (posThresh + negThresh) >> 1;
q15_t threshold = posThresh - centre;
DEBUG5("P25RX: pos/neg/centre/threshold", posThresh, negThresh, centre, threshold);
if (m_averagePtr == NOAVEPTR) {
for (uint8_t i = 0U; i < 16U; i++) {
m_centre[i] = centre;
m_threshold[i] = threshold;
}
m_averagePtr = 0U;
} else {
m_centre[m_averagePtr] = centre;
m_threshold[m_averagePtr] = threshold;
m_averagePtr++;
if (m_averagePtr >= 16U)
m_averagePtr = 0U;
}
m_centreVal = 0;
m_thresholdVal = 0;
for (uint8_t i = 0U; i < 16U; i++) {
m_centreVal += m_centre[i];
m_thresholdVal += m_threshold[i];
}
m_centreVal >>= 4;
m_thresholdVal >>= 4;
}
void CP25RX::samplesToBits(uint16_t start, uint16_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold)
{
for (uint16_t i = 0U; i < count; i++) {
q15_t sample = m_buffer[start] - centre;
if (sample < -threshold) {
WRITE_BIT1(buffer, offset, false);
offset++;
WRITE_BIT1(buffer, offset, true);
offset++;
} else if (sample < 0) {
WRITE_BIT1(buffer, offset, false);
offset++;
WRITE_BIT1(buffer, offset, false);
offset++;
} else if (sample < threshold) {
WRITE_BIT1(buffer, offset, true);
offset++;
WRITE_BIT1(buffer, offset, false);
offset++;
} else {
WRITE_BIT1(buffer, offset, true);
offset++;
WRITE_BIT1(buffer, offset, true);
offset++;
}
start += P25_RADIO_SYMBOL_LENGTH;
if (start >= P25_LDU_FRAME_LENGTH_SAMPLES)
start -= P25_LDU_FRAME_LENGTH_SAMPLES;
}
}
void CP25RX::writeRSSILdu(uint8_t* ldu)
{
#if defined(SEND_RSSI_DATA)
if (m_rssiCount > 0U) {
uint16_t rssi = m_rssiAccum / m_rssiCount;
ldu[217U] = (rssi >> 8) & 0xFFU;
ldu[218U] = (rssi >> 0) & 0xFFU;
serial.writeP25Ldu(ldu, P25_LDU_FRAME_LENGTH_BYTES + 3U);
} else {
serial.writeP25Ldu(ldu, P25_LDU_FRAME_LENGTH_BYTES + 1U);
}
#else
serial.writeP25Ldu(ldu, P25_LDU_FRAME_LENGTH_BYTES + 1U);
#endif
m_rssiAccum = 0U;
m_rssiCount = 0U;
}
#if defined(DUMP_SAMPLES)
void CP25RX::writeSamples(uint16_t start, uint8_t control)
{
q15_t samples[P25_LDU_FRAME_LENGTH_SYMBOLS];
for (uint16_t i = 0U; i < P25_LDU_FRAME_LENGTH_SYMBOLS; i++) {
samples[i] = m_buffer[start];
start += P25_RADIO_SYMBOL_LENGTH;
if (start >= P25_LDU_FRAME_LENGTH_SAMPLES)
start -= P25_LDU_FRAME_LENGTH_SAMPLES;
}
serial.writeSamples(STATE_P25, control, samples, P25_LDU_FRAME_LENGTH_SYMBOLS);
}
#endif

73
P25RX.h Normal file
View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(P25RX_H)
#define P25RX_H
#include "Config.h"
#include "P25Defines.h"
enum P25RX_STATE {
P25RXS_NONE,
P25RXS_HDR,
P25RXS_LDU
};
class CP25RX {
public:
CP25RX();
void samples(const q15_t* samples, uint16_t* rssi, uint8_t length);
void reset();
private:
P25RX_STATE m_state;
uint32_t m_bitBuffer[P25_RADIO_SYMBOL_LENGTH];
q15_t m_buffer[P25_LDU_FRAME_LENGTH_SAMPLES];
uint16_t m_bitPtr;
uint16_t m_dataPtr;
uint16_t m_hdrStartPtr;
uint16_t m_lduStartPtr;
uint16_t m_lduEndPtr;
uint16_t m_minSyncPtr;
uint16_t m_maxSyncPtr;
uint16_t m_hdrSyncPtr;
uint16_t m_lduSyncPtr;
q31_t m_maxCorr;
uint16_t m_lostCount;
uint8_t m_countdown;
q15_t m_centre[16U];
q15_t m_centreVal;
q15_t m_threshold[16U];
q15_t m_thresholdVal;
uint8_t m_averagePtr;
uint32_t m_rssiAccum;
uint16_t m_rssiCount;
void processNone(q15_t sample);
void processHdr(q15_t sample);
void processLdu(q15_t sample);
bool correlateSync();
void calculateLevels(uint16_t start, uint16_t count);
void samplesToBits(uint16_t start, uint16_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void writeRSSILdu(uint8_t* ldu);
void writeSamples(uint16_t start, uint8_t control);
};
#endif

195
P25TX.cpp Normal file
View File

@ -0,0 +1,195 @@
/*
* Copyright (C) 2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "P25TX.h"
#include "P25Defines.h"
#if defined(WIDE_C4FSK_FILTERS_TX)
// Generated using rcosdesign(0.2, 4, 5, 'sqrt') in MATLAB
static q15_t P25_C4FSK_FILTER[] = {688, -680, -2158, -3060, -2724, -775, 2684, 7041, 11310, 14425, 15565, 14425,
11310, 7041, 2684, -775, -2724, -3060, -2158, -680, 688, 0};
const uint16_t P25_C4FSK_FILTER_LEN = 22U;
#else
// Generated using rcosdesign(0.2, 8, 5, 'sqrt') in MATLAB
static q15_t P25_C4FSK_FILTER[] = {401, 104, -340, -731, -847, -553, 112, 909, 1472, 1450, 683, -675, -2144, -3040, -2706, -770, 2667, 6995,
11237, 14331, 15464, 14331, 11237, 6995, 2667, -770, -2706, -3040, -2144, -675, 683, 1450, 1472, 909, 112,
-553, -847, -731, -340, 104, 401, 0};
const uint16_t P25_C4FSK_FILTER_LEN = 42U;
#endif
// Generated in MATLAB using the following commands, and then normalised for unity gain
// shape2 = 'Inverse-sinc Lowpass';
// d2 = fdesign.interpolator(2, shape2);
// h2 = design(d2, 'SystemObject', true);
static q15_t P25_LP_FILTER[] = {170, 401, 340, -203, -715, -478, 281, 419, -440, -1002, -103, 1114, 528, -1389, -1520, 1108, 2674, -388, -4662,
-2132, 9168, 20241, 20241, 9168, -2132, -4662, -388, 2674, 1108, -1520, -1389, 528, 1114, -103, -1002, -440, 419,
281, -478, -715, -203, 340, 401, 170};
const uint16_t P25_LP_FILTER_LEN = 44U;
const q15_t P25_LEVELA[] = { 495, 495, 495, 495, 495};
const q15_t P25_LEVELB[] = { 165, 165, 165, 165, 165};
const q15_t P25_LEVELC[] = {-165, -165, -165, -165, -165};
const q15_t P25_LEVELD[] = {-495, -495, -495, -495, -495};
const uint8_t P25_START_SYNC = 0x77U;
CP25TX::CP25TX() :
m_buffer(1500U),
m_modFilter(),
m_lpFilter(),
m_modState(),
m_lpState(),
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U),
m_txDelay(240U), // 200ms
m_count(0U)
{
::memset(m_modState, 0x00U, 70U * sizeof(q15_t));
::memset(m_lpState, 0x00U, 70U * sizeof(q15_t));
m_modFilter.numTaps = P25_C4FSK_FILTER_LEN;
m_modFilter.pState = m_modState;
m_modFilter.pCoeffs = P25_C4FSK_FILTER;
m_lpFilter.numTaps = P25_LP_FILTER_LEN;
m_lpFilter.pState = m_lpState;
m_lpFilter.pCoeffs = P25_LP_FILTER;
}
void CP25TX::process()
{
if (m_buffer.getData() == 0U && m_poLen == 0U)
return;
if (m_poLen == 0U) {
if (!m_tx) {
m_count = 0U;
for (uint16_t i = 0U; i < m_txDelay; i++)
m_poBuffer[m_poLen++] = P25_START_SYNC;
} else {
uint8_t length = m_buffer.get();
for (uint8_t i = 0U; i < length; i++) {
uint8_t c = m_buffer.get();
m_poBuffer[m_poLen++] = c;
}
}
m_poPtr = 0U;
}
if (m_poLen > 0U) {
uint16_t space = io.getSpace();
while (space > (4U * P25_RADIO_SYMBOL_LENGTH)) {
uint8_t c = m_poBuffer[m_poPtr++];
writeByte(c);
space -= 4U * P25_RADIO_SYMBOL_LENGTH;
if (m_poPtr >= m_poLen) {
m_poPtr = 0U;
m_poLen = 0U;
return;
}
}
}
}
uint8_t CP25TX::writeData(const uint8_t* data, uint8_t length)
{
if (length < (P25_TERM_FRAME_LENGTH_BYTES + 1U))
return 4U;
uint16_t space = m_buffer.getSpace();
if (space < length)
return 5U;
m_buffer.put(length - 1U);
for (uint8_t i = 0U; i < (length - 1U); i++)
m_buffer.put(data[i + 1U]);
return 0U;
}
void CP25TX::writeByte(uint8_t c)
{
q15_t inBuffer[P25_RADIO_SYMBOL_LENGTH * 4U + 1U];
q15_t intBuffer[P25_RADIO_SYMBOL_LENGTH * 4U + 1U];
q15_t outBuffer[P25_RADIO_SYMBOL_LENGTH * 4U + 1U];
const uint8_t MASK = 0xC0U;
q15_t* p = inBuffer;
for (uint8_t i = 0U; i < 4U; i++, c <<= 2, p += P25_RADIO_SYMBOL_LENGTH) {
switch (c & MASK) {
case 0xC0U:
::memcpy(p, P25_LEVELA, P25_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x80U:
::memcpy(p, P25_LEVELB, P25_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x00U:
::memcpy(p, P25_LEVELC, P25_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
default:
::memcpy(p, P25_LEVELD, P25_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
}
}
uint16_t blockSize = P25_RADIO_SYMBOL_LENGTH * 4U;
// Handle the case of the oscillator not being accurate enough
if (m_sampleCount > 0U) {
m_count += P25_RADIO_SYMBOL_LENGTH * 4U;
if (m_count >= m_sampleCount) {
if (m_sampleInsert) {
inBuffer[P25_RADIO_SYMBOL_LENGTH * 4U] = inBuffer[P25_RADIO_SYMBOL_LENGTH * 4U - 1U];
blockSize++;
} else {
blockSize--;
}
m_count -= m_sampleCount;
}
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, intBuffer, blockSize);
::arm_fir_fast_q15(&m_lpFilter, intBuffer, outBuffer, blockSize);
io.write(STATE_P25, outBuffer, blockSize);
}
void CP25TX::setTXDelay(uint8_t delay)
{
m_txDelay = 600U + uint16_t(delay) * 12U; // 500ms + tx delay
}
uint16_t CP25TX::getSpace() const
{
return m_buffer.getSpace() / P25_LDU_FRAME_LENGTH_BYTES;
}

54
P25TX.h Normal file
View File

@ -0,0 +1,54 @@
/*
* Copyright (C) 2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if !defined(P25TX_H)
#define P25TX_H
#include "Config.h"
#include "SerialRB.h"
class CP25TX {
public:
CP25TX();
uint8_t writeData(const uint8_t* data, uint8_t length);
void process();
void setTXDelay(uint8_t delay);
uint16_t getSpace() const;
private:
CSerialRB m_buffer;
arm_fir_instance_q15 m_modFilter;
arm_fir_instance_q15 m_lpFilter;
q15_t m_modState[70U]; // NoTaps + BlockSize - 1, 42 + 20 - 1 plus some spare
q15_t m_lpState[70U]; // NoTaps + BlockSize - 1, 44 + 20 - 1 plus some spare
uint8_t m_poBuffer[1200U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint16_t m_txDelay;
uint32_t m_count;
void writeByte(uint8_t c);
};
#endif

View File

@ -1,9 +1,7 @@
This is the source code of the MMDVM firmware that supports D-Star, DMR, and System Fusion.
This is the source code of the MMDVM firmware that supports D-Star, DMR, System Fusion and P25 modes.
Currently it only runs on the Arduino Due, but other platforms are planned.
It runs on the Arduino Due, the ST-Micro STM32F407-DISCO and STM32F446-NUCLEO, as well as the Teensy 3.1/3.2/3.5/3.6. What these platforms have in common is the use of an ARM Cortex-M3 or M4 processor with a clock speed greater than 70 MHz, and access to at least one analogue to digital converter and one digital to analogue converter. A Cortex-M7 processor is also probably adequate.
In order to build this software you will need to edit a file within the Arduino GUI and that is detailed in the BUILD.txt file.
In order to build this software for the Arduino Due, you will need to edit a file within the Arduino GUI and that is detailed in the BUILD.txt file. The STM32 support is being supplied via the Coocox IDE with ARM GCC. The Teensy support is via the latest beta of Teensyduino.
This software is licenced under the GPL v2 and is intended for amateur and educational use only. Use of this software for commercial purposes is strictly forbidden.
It is only to be used on the main DMR+ and main BrandMeister networks. If you wish to use it on any other network, you must get written permission from myself, G4KLX. Each such request will be dealt with on a case-by-case basis.

104
RSSIRB.cpp Normal file
View File

@ -0,0 +1,104 @@
/*
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_rssi(NULL),
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;
}

55
RSSIRB.h Normal file
View File

@ -0,0 +1,55 @@
/*
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) || defined(STM32F4)
#include "stm32f4xx.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

@ -19,7 +19,6 @@ Boston, MA 02110-1301, USA.
*/
#include "SampleRB.h"
#include "Debug.h"
CSampleRB::CSampleRB(uint16_t length) :
m_length(length),
@ -36,12 +35,19 @@ m_overflow(false)
uint16_t CSampleRB::getSpace() const
{
uint16_t n = 0U;
if (m_tail == m_head)
return m_full ? 0U : m_length;
n = m_full ? 0U : m_length;
else if (m_tail < m_head)
return m_length - m_head + m_tail;
n = m_length - m_head + m_tail;
else
return m_tail - m_head;
n = m_tail - m_head;
if (n > m_length)
n = 0U;
return n;
}
uint16_t CSampleRB::getData() const

View File

@ -21,8 +21,9 @@ Boston, MA 02110-1301, USA.
#if !defined(SAMPLERB_H)
#define SAMPLERB_H
#if defined(__MBED__)
#include "mbed.h"
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif

95
SerialArduino.cpp Normal file
View File

@ -0,0 +1,95 @@
/*
* Copyright (C) 2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "SerialPort.h"
#if defined(__SAM3X8E__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
void CSerialPort::beginInt(uint8_t n, int speed)
{
switch (n) {
case 1U:
Serial.begin(speed);
break;
case 2U:
Serial2.begin(speed);
break;
case 3U:
Serial3.begin(speed);
break;
default:
break;
}
}
int CSerialPort::availableInt(uint8_t n)
{
switch (n) {
case 1U:
return Serial.available();
case 2U:
return Serial2.available();
case 3U:
return Serial3.available();
default:
return false;
}
}
uint8_t CSerialPort::readInt(uint8_t n)
{
switch (n) {
case 1U:
return Serial.read();
case 2U:
return Serial2.read();
case 3U:
return Serial3.read();
default:
return 0U;
}
}
void CSerialPort::writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool flush)
{
switch (n) {
case 1U:
Serial.write(data, length);
if (flush)
Serial.flush();
break;
case 2U:
Serial2.write(data, length);
if (flush)
Serial2.flush();
break;
case 3U:
Serial3.write(data, length);
if (flush)
Serial3.flush();
break;
default:
break;
}
}
#endif

View File

@ -1,5 +1,6 @@
/*
* Copyright (C) 2013,2015,2016 by Jonathan Naylor G4KLX
* Copyright (C) 2013,2015,2016,2017 by Jonathan Naylor G4KLX
* Copyright (C) 2016 by Colin Durbridge G4EML
*
* 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
@ -16,6 +17,8 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
@ -30,6 +33,9 @@ const uint8_t MMDVM_SET_MODE = 0x03U;
const uint8_t MMDVM_SET_FREQ = 0x04U;
const uint8_t MMDVM_CAL_DATA = 0x08U;
const uint8_t MMDVM_RSSI_DATA = 0x09U;
const uint8_t MMDVM_SEND_CWID = 0x0AU;
const uint8_t MMDVM_DSTAR_HEADER = 0x10U;
const uint8_t MMDVM_DSTAR_DATA = 0x11U;
@ -42,37 +48,46 @@ const uint8_t MMDVM_DMR_DATA2 = 0x1AU;
const uint8_t MMDVM_DMR_LOST2 = 0x1BU;
const uint8_t MMDVM_DMR_SHORTLC = 0x1CU;
const uint8_t MMDVM_DMR_START = 0x1DU;
const uint8_t MMDVM_DMR_ABORT = 0x1EU;
const uint8_t MMDVM_YSF_DATA = 0x20U;
const uint8_t MMDVM_YSF_LOST = 0x21U;
const uint8_t MMDVM_P25_HDR = 0x30U;
const uint8_t MMDVM_P25_LDU = 0x31U;
const uint8_t MMDVM_P25_LOST = 0x32U;
const uint8_t MMDVM_ACK = 0x70U;
const uint8_t MMDVM_NAK = 0x7FU;
const uint8_t MMDVM_DUMP = 0xF0U;
const uint8_t MMDVM_SERIAL = 0x80U;
const uint8_t MMDVM_SAMPLES = 0xF0U;
const uint8_t MMDVM_DEBUG1 = 0xF1U;
const uint8_t MMDVM_DEBUG2 = 0xF2U;
const uint8_t MMDVM_DEBUG3 = 0xF3U;
const uint8_t MMDVM_DEBUG4 = 0xF4U;
const uint8_t MMDVM_DEBUG5 = 0xF5U;
const uint8_t MMDVM_SAMPLES = 0xF8U;
const uint8_t HARDWARE[] = "MMDVM 20160229 (D-Star/DMR/System Fusion)";
#if defined(EXTERNAL_OSC)
const uint8_t HARDWARE[] = "MMDVM 20170303 TCXO (D-Star/DMR/System Fusion/P25/RSSI/CW Id)";
#else
const uint8_t HARDWARE[] = "MMDVM 20170303 (D-Star/DMR/System Fusion/P25/RSSI/CW Id)";
#endif
const uint8_t PROTOCOL_VERSION = 1U;
CSerialPort::CSerialPort() :
#if defined(__MBED__)
m_serial(SERIAL_TX, SERIAL_RX),
#endif
m_buffer(),
m_ptr(0U),
m_len(0U)
{
}
void CSerialPort::sendACK() const
void CSerialPort::sendACK()
{
uint8_t reply[4U];
@ -81,10 +96,10 @@ void CSerialPort::sendACK() const
reply[2U] = MMDVM_ACK;
reply[3U] = m_buffer[2U];
write(reply, 4);
writeInt(1U, reply, 4);
}
void CSerialPort::sendNAK(uint8_t err) const
void CSerialPort::sendNAK(uint8_t err)
{
uint8_t reply[5U];
@ -94,18 +109,18 @@ void CSerialPort::sendNAK(uint8_t err) const
reply[3U] = m_buffer[2U];
reply[4U] = err;
write(reply, 5);
writeInt(1U, reply, 5);
}
void CSerialPort::getStatus() const
void CSerialPort::getStatus()
{
io.resetWatchdog();
uint8_t reply[11U];
uint8_t reply[15U];
// Send all sorts of interesting internal values
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 10U;
reply[1U] = 11U;
reply[2U] = MMDVM_GET_STATUS;
reply[3U] = 0x00U;
@ -115,12 +130,18 @@ void CSerialPort::getStatus() const
reply[3U] |= 0x02U;
if (m_ysfEnable)
reply[3U] |= 0x04U;
if (m_p25Enable)
reply[3U] |= 0x08U;
reply[4U] = uint8_t(m_modemState);
reply[5U] = m_tx ? 0x01U : 0x00U;
reply[5U] = m_tx ? 0x01U : 0x00U;
if (io.hasADCOverflow())
bool adcOverflow;
bool dacOverflow;
io.getOverflow(adcOverflow, dacOverflow);
if (adcOverflow)
reply[5U] |= 0x02U;
if (io.hasRXOverflow())
@ -129,14 +150,27 @@ void CSerialPort::getStatus() const
if (io.hasTXOverflow())
reply[5U] |= 0x08U;
if (io.hasLockout())
reply[5U] |= 0x10U;
if (dacOverflow)
reply[5U] |= 0x20U;
reply[5U] |= m_dcd ? 0x40U : 0x00U;
if (m_dstarEnable)
reply[6U] = dstarTX.getSpace();
else
reply[6U] = 0U;
if (m_dmrEnable) {
reply[7U] = dmrTX.getSpace1();
reply[8U] = dmrTX.getSpace2();
if (m_duplex) {
reply[7U] = dmrTX.getSpace1();
reply[8U] = dmrTX.getSpace2();
} else {
reply[7U] = 10U;
reply[8U] = dmrDMOTX.getSpace();
}
} else {
reply[7U] = 0U;
reply[8U] = 0U;
@ -147,10 +181,15 @@ void CSerialPort::getStatus() const
else
reply[9U] = 0U;
write(reply, 10);
if (m_p25Enable)
reply[10U] = p25TX.getSpace();
else
reply[10U] = 0U;
writeInt(1U, reply, 11);
}
void CSerialPort::getVersion() const
void CSerialPort::getVersion()
{
uint8_t reply[100U];
@ -166,21 +205,23 @@ void CSerialPort::getVersion() const
reply[1U] = count;
write(reply, count);
writeInt(1U, reply, count);
}
uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
{
if (length < 7U)
if (length < 13U)
return 4U;
bool rxInvert = (data[0U] & 0x01U) == 0x01U;
bool txInvert = (data[0U] & 0x02U) == 0x02U;
bool pttInvert = (data[0U] & 0x04U) == 0x04U;
bool simplex = (data[0U] & 0x80U) == 0x80U;
bool dstarEnable = (data[1U] & 0x01U) == 0x01U;
bool dmrEnable = (data[1U] & 0x02U) == 0x02U;
bool ysfEnable = (data[1U] & 0x04U) == 0x04U;
bool p25Enable = (data[1U] & 0x08U) == 0x08U;
uint8_t txDelay = data[2U];
if (txDelay > 50U)
@ -188,7 +229,7 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
MMDVM_STATE modemState = MMDVM_STATE(data[3U]);
if (modemState != STATE_IDLE && modemState != STATE_DSTAR && modemState != STATE_DMR && modemState != STATE_YSF && modemState != STATE_CALIBRATE)
if (modemState != STATE_IDLE && modemState != STATE_DSTAR && modemState != STATE_DMR && modemState != STATE_YSF && modemState != STATE_P25 && modemState != STATE_DSTARCAL && modemState != STATE_DMRCAL && modemState != STATE_RSSICAL)
return 4U;
if (modemState == STATE_DSTAR && !dstarEnable)
return 4U;
@ -196,28 +237,55 @@ uint8_t CSerialPort::setConfig(const uint8_t* data, uint8_t length)
return 4U;
if (modemState == STATE_YSF && !ysfEnable)
return 4U;
if (modemState == STATE_P25 && !p25Enable)
return 4U;
uint8_t rxLevel = data[4U];
uint8_t txLevel = data[5U];
uint8_t colorCode = data[6U];
if (colorCode > 15U)
return 4U;
uint8_t dmrDelay = data[7U];
int8_t oscOffset = int8_t(data[8U]) - 128;
if (oscOffset < 0) {
m_sampleCount = 1000000U / uint32_t(-oscOffset);
m_sampleInsert = false;
} else if (oscOffset > 0) {
m_sampleCount = 1000000U / uint32_t(oscOffset);
m_sampleInsert = true;
} else {
m_sampleCount = 0U;
m_sampleInsert = false;
}
uint8_t cwIdTXLevel = data[5U];
uint8_t dstarTXLevel = data[9U];
uint8_t dmrTXLevel = data[10U];
uint8_t ysfTXLevel = data[11U];
uint8_t p25TXLevel = data[12U];
m_modemState = modemState;
m_dstarEnable = dstarEnable;
m_dmrEnable = dmrEnable;
m_ysfEnable = ysfEnable;
m_p25Enable = p25Enable;
m_duplex = !simplex;
dstarTX.setTXDelay(txDelay);
ysfTX.setTXDelay(txDelay);
p25TX.setTXDelay(txDelay);
dmrDMOTX.setTXDelay(txDelay);
dmrTX.setColorCode(colorCode);
dmrRX.setColorCode(colorCode);
dmrRX.setDelay(dmrDelay);
dmrDMORX.setColorCode(colorCode);
dmrIdleRX.setColorCode(colorCode);
io.setParameters(rxInvert, txInvert, pttInvert, rxLevel, txLevel);
io.setParameters(rxInvert, txInvert, pttInvert, rxLevel, cwIdTXLevel, dstarTXLevel, dmrTXLevel, ysfTXLevel, p25TXLevel);
io.start();
@ -234,7 +302,7 @@ uint8_t CSerialPort::setMode(const uint8_t* data, uint8_t length)
if (modemState == m_modemState)
return 0U;
if (modemState != STATE_IDLE && modemState != STATE_DSTAR && modemState != STATE_DMR && modemState != STATE_YSF && modemState != STATE_CALIBRATE)
if (modemState != STATE_IDLE && modemState != STATE_DSTAR && modemState != STATE_DMR && modemState != STATE_YSF && modemState != STATE_P25 && modemState != STATE_DSTARCAL && modemState != STATE_DMRCAL && modemState != STATE_RSSICAL)
return 4U;
if (modemState == STATE_DSTAR && !m_dstarEnable)
return 4U;
@ -242,6 +310,8 @@ uint8_t CSerialPort::setMode(const uint8_t* data, uint8_t length)
return 4U;
if (modemState == STATE_YSF && !m_ysfEnable)
return 4U;
if (modemState == STATE_P25 && !m_p25Enable)
return 4U;
setMode(modemState);
@ -255,25 +325,65 @@ void CSerialPort::setMode(MMDVM_STATE modemState)
DEBUG1("Mode set to DMR");
dstarRX.reset();
ysfRX.reset();
p25RX.reset();
cwIdTX.reset();
break;
case STATE_DSTAR:
DEBUG1("Mode set to D-Star");
dmrIdleRX.reset();
dmrDMORX.reset();
dmrRX.reset();
ysfRX.reset();
p25RX.reset();
cwIdTX.reset();
break;
case STATE_YSF:
DEBUG1("Mode set to System Fusion");
dmrIdleRX.reset();
dmrDMORX.reset();
dmrRX.reset();
dstarRX.reset();
p25RX.reset();
cwIdTX.reset();
break;
case STATE_CALIBRATE:
DEBUG1("Mode set to Calibrate");
case STATE_P25:
DEBUG1("Mode set to P25");
dmrIdleRX.reset();
dmrDMORX.reset();
dmrRX.reset();
dstarRX.reset();
ysfRX.reset();
cwIdTX.reset();
break;
case STATE_DSTARCAL:
DEBUG1("Mode set to D-Star Calibrate");
dmrIdleRX.reset();
dmrDMORX.reset();
dmrRX.reset();
dstarRX.reset();
ysfRX.reset();
p25RX.reset();
cwIdTX.reset();
break;
case STATE_DMRCAL:
DEBUG1("Mode set to DMR Calibrate");
dmrIdleRX.reset();
dmrDMORX.reset();
dmrRX.reset();
dstarRX.reset();
ysfRX.reset();
p25RX.reset();
cwIdTX.reset();
break;
case STATE_RSSICAL:
DEBUG1("Mode set to RSSI Calibrate");
dmrIdleRX.reset();
dmrDMORX.reset();
dmrRX.reset();
dstarRX.reset();
ysfRX.reset();
p25RX.reset();
cwIdTX.reset();
break;
default:
DEBUG1("Mode set to Idle");
@ -282,47 +392,40 @@ void CSerialPort::setMode(MMDVM_STATE modemState)
}
m_modemState = modemState;
io.setMode();
}
void CSerialPort::start()
{
#if defined(__MBED__)
m_serial.baud(115200);
#else
Serial.begin(115200);
beginInt(1U, 115200);
#if defined(SERIAL_REPEATER)
beginInt(3U, 9600);
#endif
}
void CSerialPort::process()
{
#if defined(__MBED__)
while (m_serial.readable()) {
uint8_t c = m_serial.getc();
#else
while (Serial.available()) {
uint8_t c = Serial.read();
#endif
while (availableInt(1U)) {
uint8_t c = readInt(1U);
if (m_ptr == 0U && c == MMDVM_FRAME_START) {
// Handle the frame start correctly
m_buffer[0U] = c;
m_ptr = 1U;
m_len = 0U;
} else if (m_ptr > 0U) {
if (m_ptr == 0U) {
if (c == MMDVM_FRAME_START) {
// Handle the frame start correctly
m_buffer[0U] = c;
m_ptr = 1U;
m_len = 0U;
}
} else if (m_ptr == 1U) {
// Handle the frame length
m_len = m_buffer[m_ptr] = c;
m_ptr = 2U;
} else {
// Any other bytes are added to the buffer
m_buffer[m_ptr] = c;
m_ptr++;
// Once we have enough bytes, calculate the expected length
if (m_ptr == 2U)
m_len = m_buffer[1U];
if (m_ptr == 3U && m_len > 130U) {
sendNAK(3U);
m_ptr = 0U;
m_len = 0U;
}
// The full packet has been received, process it
if (m_ptr == m_len) {
uint8_t err = 2U;
@ -357,8 +460,10 @@ void CSerialPort::process()
break;
case MMDVM_CAL_DATA:
if (m_modemState == STATE_CALIBRATE)
err = calTX.write(m_buffer + 3U, m_len - 3U);
if (m_modemState == STATE_DSTARCAL)
err = calDStarTX.write(m_buffer + 3U, m_len - 3U);
if (m_modemState == STATE_DMRCAL)
err = calDMR.write(m_buffer + 3U, m_len - 3U);
if (err == 0U) {
sendACK();
} else {
@ -367,6 +472,16 @@ void CSerialPort::process()
}
break;
case MMDVM_SEND_CWID:
err = 5U;
if (m_modemState == STATE_IDLE)
err = cwIdTX.write(m_buffer + 3U, m_len - 3U);
if (err != 0U) {
DEBUG2("Invalid CW Id data", err);
sendNAK(err);
}
break;
case MMDVM_DSTAR_HEADER:
if (m_dstarEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DSTAR)
@ -411,8 +526,10 @@ void CSerialPort::process()
case MMDVM_DMR_DATA1:
if (m_dmrEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR)
err = dmrTX.writeData1(m_buffer + 3U, m_len - 3U);
if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR) {
if (m_duplex)
err = dmrTX.writeData1(m_buffer + 3U, m_len - 3U);
}
}
if (err == 0U) {
if (m_modemState == STATE_IDLE)
@ -425,8 +542,12 @@ void CSerialPort::process()
case MMDVM_DMR_DATA2:
if (m_dmrEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR)
err = dmrTX.writeData2(m_buffer + 3U, m_len - 3U);
if (m_modemState == STATE_IDLE || m_modemState == STATE_DMR) {
if (m_duplex)
err = dmrTX.writeData2(m_buffer + 3U, m_len - 3U);
else
err = dmrDMOTX.writeData(m_buffer + 3U, m_len - 3U);
}
}
if (err == 0U) {
if (m_modemState == STATE_IDLE)
@ -441,13 +562,13 @@ void CSerialPort::process()
if (m_dmrEnable) {
err = 4U;
if (m_len == 4U) {
if (m_buffer[3U] == 0x01U && m_modemState == STATE_IDLE) {
dmrTX.setStart(true);
setMode(STATE_DMR);
if (m_buffer[3U] == 0x01U && m_modemState == STATE_DMR) {
if (!m_tx)
dmrTX.setStart(true);
err = 0U;
} else if (m_buffer[3U] == 0x00U && m_modemState == STATE_DMR) {
dmrTX.setStart(false);
setMode(STATE_IDLE);
if (m_tx)
dmrTX.setStart(false);
err = 0U;
}
}
@ -467,6 +588,15 @@ void CSerialPort::process()
}
break;
case MMDVM_DMR_ABORT:
if (m_dmrEnable)
err = dmrTX.writeAbort(m_buffer + 3U, m_len - 3U);
if (err != 0U) {
DEBUG2("Received invalid DMR Abort", err);
sendNAK(err);
}
break;
case MMDVM_YSF_DATA:
if (m_ysfEnable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_YSF)
@ -481,6 +611,40 @@ void CSerialPort::process()
}
break;
case MMDVM_P25_HDR:
if (m_p25Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_P25)
err = p25TX.writeData(m_buffer + 3U, m_len - 3U);
}
if (err == 0U) {
if (m_modemState == STATE_IDLE)
setMode(STATE_P25);
} else {
DEBUG2("Received invalid P25 header", err);
sendNAK(err);
}
break;
case MMDVM_P25_LDU:
if (m_p25Enable) {
if (m_modemState == STATE_IDLE || m_modemState == STATE_P25)
err = p25TX.writeData(m_buffer + 3U, m_len - 3U);
}
if (err == 0U) {
if (m_modemState == STATE_IDLE)
setMode(STATE_P25);
} else {
DEBUG2("Received invalid P25 LDU", err);
sendNAK(err);
}
break;
#if defined(SERIAL_REPEATER)
case MMDVM_SERIAL:
writeInt(3U, m_buffer + 3U, m_len - 3U);
break;
#endif
default:
// Handle this, send a NAK back
sendNAK(1U);
@ -492,6 +656,12 @@ void CSerialPort::process()
}
}
}
#if defined(SERIAL_REPEATER)
// Drain any incoming serial data
while (availableInt(3U))
readInt(3U);
#endif
}
void CSerialPort::writeDStarHeader(const uint8_t* header, uint8_t length)
@ -513,7 +683,7 @@ void CSerialPort::writeDStarHeader(const uint8_t* header, uint8_t length)
reply[1U] = count;
write(reply, count);
writeInt(1U, reply, count);
}
void CSerialPort::writeDStarData(const uint8_t* data, uint8_t length)
@ -536,7 +706,7 @@ void CSerialPort::writeDStarData(const uint8_t* data, uint8_t length)
reply[1U] = count;
write(reply, count);
writeInt(1U, reply, count);
}
void CSerialPort::writeDStarLost()
@ -553,7 +723,7 @@ void CSerialPort::writeDStarLost()
reply[1U] = 3U;
reply[2U] = MMDVM_DSTAR_LOST;
write(reply, 3);
writeInt(1U, reply, 3);
}
void CSerialPort::writeDStarEOT()
@ -570,7 +740,7 @@ void CSerialPort::writeDStarEOT()
reply[1U] = 3U;
reply[2U] = MMDVM_DSTAR_EOT;
write(reply, 3);
writeInt(1U, reply, 3);
}
void CSerialPort::writeDMRData(bool slot, const uint8_t* data, uint8_t length)
@ -593,7 +763,7 @@ void CSerialPort::writeDMRData(bool slot, const uint8_t* data, uint8_t length)
reply[1U] = count;
write(reply, count);
writeInt(1U, reply, count);
}
void CSerialPort::writeDMRLost(bool slot)
@ -610,7 +780,7 @@ void CSerialPort::writeDMRLost(bool slot)
reply[1U] = 3U;
reply[2U] = slot ? MMDVM_DMR_LOST2 : MMDVM_DMR_LOST1;
write(reply, 3);
writeInt(1U, reply, 3);
}
void CSerialPort::writeYSFData(const uint8_t* data, uint8_t length)
@ -633,7 +803,7 @@ void CSerialPort::writeYSFData(const uint8_t* data, uint8_t length)
reply[1U] = count;
write(reply, count);
writeInt(1U, reply, count);
}
void CSerialPort::writeYSFLost()
@ -650,12 +820,75 @@ void CSerialPort::writeYSFLost()
reply[1U] = 3U;
reply[2U] = MMDVM_YSF_LOST;
write(reply, 3);
writeInt(1U, reply, 3);
}
void CSerialPort::writeP25Hdr(const uint8_t* data, uint8_t length)
{
if (m_modemState != STATE_P25 && m_modemState != STATE_IDLE)
return;
if (!m_p25Enable)
return;
uint8_t reply[120U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 0U;
reply[2U] = MMDVM_P25_HDR;
uint8_t count = 3U;
for (uint8_t i = 0U; i < length; i++, count++)
reply[count] = data[i];
reply[1U] = count;
writeInt(1U, reply, count);
}
void CSerialPort::writeP25Ldu(const uint8_t* data, uint8_t length)
{
if (m_modemState != STATE_P25 && m_modemState != STATE_IDLE)
return;
if (!m_p25Enable)
return;
uint8_t reply[250U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 0U;
reply[2U] = MMDVM_P25_LDU;
uint8_t count = 3U;
for (uint8_t i = 0U; i < length; i++, count++)
reply[count] = data[i];
reply[1U] = count;
writeInt(1U, reply, count);
}
void CSerialPort::writeP25Lost()
{
if (m_modemState != STATE_P25 && m_modemState != STATE_IDLE)
return;
if (!m_p25Enable)
return;
uint8_t reply[3U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 3U;
reply[2U] = MMDVM_P25_LOST;
writeInt(1U, reply, 3);
}
void CSerialPort::writeCalData(const uint8_t* data, uint8_t length)
{
if (m_modemState != STATE_CALIBRATE)
if (m_modemState != STATE_DSTARCAL)
return;
uint8_t reply[130U];
@ -670,58 +903,52 @@ void CSerialPort::writeCalData(const uint8_t* data, uint8_t length)
reply[1U] = count;
write(reply, count);
writeInt(1U, reply, count);
}
void CSerialPort::write(const uint8_t* data, uint16_t length, bool flush) const
void CSerialPort::writeRSSIData(const uint8_t* data, uint8_t length)
{
#if defined(__MBED__)
for (uint16_t i = 0U; i < length; i++)
m_serial.putc(data[i]);
// No explicit flush function
#else
Serial.write(data, length);
if (flush)
Serial.flush();
#endif
}
if (m_modemState != STATE_RSSICAL)
return;
#if defined(WANT_DEBUG)
void CSerialPort::writeDump(const uint8_t* data, uint8_t length)
{
ASSERT(length <= 252U);
uint8_t reply[255U];
uint8_t reply[30U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 0U;
reply[2U] = MMDVM_DUMP;
reply[2U] = MMDVM_RSSI_DATA;
uint8_t count = length * sizeof(uint8_t) + 3U;
::memcpy(reply + 3U, data, length * sizeof(uint8_t));
uint8_t count = 3U;
for (uint8_t i = 0U; i < length; i++, count++)
reply[count] = data[i];
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count);
}
void CSerialPort::writeSamples(const q15_t* data, uint8_t length)
void CSerialPort::writeSamples(uint8_t mode, uint8_t control, const q15_t* samples, uint16_t nSamples)
{
ASSERT(length <= 126U);
uint8_t reply[255U];
uint8_t reply[1800U];
reply[0U] = MMDVM_FRAME_START;
reply[1U] = 0U;
reply[2U] = MMDVM_SAMPLES;
uint8_t count = length * sizeof(q15_t) + 3U;
::memcpy(reply + 3U, data, length * sizeof(q15_t));
reply[5U] = mode;
reply[6U] = control;
reply[1U] = count;
uint16_t count = 7U;
for (uint16_t i = 0U; i < nSamples; i++) {
uint16_t val = uint16_t(samples[i] + 2048);
write(reply, count, true);
reply[count++] = (val >> 8) & 0xFF;
reply[count++] = (val >> 0) & 0xFF;
}
reply[3U] = (count >> 8) & 0xFFU;
reply[4U] = (count >> 0) & 0xFFU;
writeInt(1U, reply, count, true);
}
void CSerialPort::writeDebug(const char* text)
@ -738,7 +965,7 @@ void CSerialPort::writeDebug(const char* text)
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count, true);
}
void CSerialPort::writeDebug(const char* text, int16_t n1)
@ -758,7 +985,7 @@ void CSerialPort::writeDebug(const char* text, int16_t n1)
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count, true);
}
void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2)
@ -781,7 +1008,7 @@ void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2)
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count, true);
}
void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n3)
@ -807,7 +1034,7 @@ void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count, true);
}
void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n3, int16_t n4)
@ -836,7 +1063,7 @@ void CSerialPort::writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count, true);
}
void CSerialPort::writeAssert(bool cond, const char* text, const char* file, long line)
@ -864,8 +1091,6 @@ void CSerialPort::writeAssert(bool cond, const char* text, const char* file, lon
reply[1U] = count;
write(reply, count, true);
writeInt(1U, reply, count, true);
}
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -42,35 +42,41 @@ public:
void writeYSFData(const uint8_t* data, uint8_t length);
void writeYSFLost();
void writeCalData(const uint8_t* data, uint8_t length);
void writeP25Hdr(const uint8_t* data, uint8_t length);
void writeP25Ldu(const uint8_t* data, uint8_t length);
void writeP25Lost();
void writeCalData(const uint8_t* data, uint8_t length);
void writeRSSIData(const uint8_t* data, uint8_t length);
void writeSamples(uint8_t mode, uint8_t control, const q15_t* samples, uint16_t nSamples);
#if defined(WANT_DEBUG)
void writeDump(const uint8_t* data, uint8_t length);
void writeSamples(const q15_t* data, uint8_t length);
void writeDebug(const char* text);
void writeDebug(const char* text, int16_t n1);
void writeDebug(const char* text, int16_t n1, int16_t n2);
void writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n3);
void writeDebug(const char* text, int16_t n1, int16_t n2, int16_t n3, int16_t n4);
void writeAssert(bool cond, const char* text, const char* file, long line);
#endif
private:
#if defined(__MBED__)
Serial m_serial;
#endif
uint8_t m_buffer[130U];
uint8_t m_buffer[256U];
uint8_t m_ptr;
uint8_t m_len;
void sendACK() const;
void sendNAK(uint8_t err) const;
void getStatus() const;
void getVersion() const;
void sendACK();
void sendNAK(uint8_t err);
void getStatus();
void getVersion();
uint8_t setConfig(const uint8_t* data, uint8_t length);
uint8_t setMode(const uint8_t* data, uint8_t length);
void write(const uint8_t* data, uint16_t length, bool flush = false) const;
void setMode(MMDVM_STATE modemState);
// Hardware versions
void beginInt(uint8_t n, int speed);
int availableInt(uint8_t n);
uint8_t readInt(uint8_t n);
void writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool flush = false);
};
#endif

View File

@ -19,7 +19,6 @@ Boston, MA 02110-1301, USA.
*/
#include "SerialRB.h"
#include "Debug.h"
CSerialRB::CSerialRB(uint16_t length) :
m_length(length),
@ -40,12 +39,19 @@ void CSerialRB::reset()
uint16_t CSerialRB::getSpace() const
{
uint16_t n = 0U;
if (m_tail == m_head)
return m_full ? 0U : m_length;
n = m_full ? 0U : m_length;
else if (m_tail < m_head)
return m_length - m_head + m_tail;
n = m_length - m_head + m_tail;
else
return m_tail - m_head;
n = m_tail - m_head;
if (n > m_length)
n = 0U;
return n;
}
uint16_t CSerialRB::getData() const

View File

@ -21,8 +21,9 @@ Boston, MA 02110-1301, USA.
#if !defined(SERIALRB_H)
#define SERIALRB_H
#if defined(__MBED__)
#include "mbed.h"
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif

910
SerialSTM.cpp Normal file
View File

@ -0,0 +1,910 @@
/*
* Copyright (C) 2016 by Jim McLaughlin KI6ZUM
* Copyright (C) 2016, 2017 by Andy Uribe CA6JAU
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#include "Config.h"
#include "Globals.h"
#include "SerialPort.h"
/*
Pin definitions:
- Host communication:
USART1 - TXD PA9 - RXD PA10 (Pi board)
USART2 - TXD PA2 - RXD PA3 (Nucleo board)
USART3 - TXD PC10 - RXD PC11 (Discovery board)
- Serial repeater:
USART1 - TXD PA9 - RXD PA10 (Nucleo with Arduino header)
UART5 - TXD PC12 - RXD PD2 (Discovery, Pi and Nucleo with Morpho header)
*/
#if defined(STM32F4XX) || defined(STM32F4)
#define TX_SERIAL_FIFO_SIZE 256U
#define RX_SERIAL_FIFO_SIZE 256U
extern "C" {
void USART1_IRQHandler();
void USART2_IRQHandler();
void USART3_IRQHandler();
void UART5_IRQHandler();
}
/* ************* USART1 ***************** */
#if defined(STM32F4_PI) || (defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER))
volatile uint32_t intcount1;
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
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()
{
uint8_t c;
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);
intcount1++;
}
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)
{
// USART1 - TXD PA9 - RXD PA10 - pins on mmdvm pi board
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource9, GPIO_AF_USART1);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource10, GPIO_AF_USART1);
// USART IRQ init
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_Init(&NVIC_InitStructure);
// Configure USART as alternate function
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9 | GPIO_Pin_10; // Tx | Rx
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
// Configure USART baud rate
USART_StructInit(&USART_InitStructure);
USART_InitStructure.USART_BaudRate = speed;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(USART1, &USART_InitStructure);
USART_Cmd(USART1, ENABLE);
USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
// initialize the fifos
TXSerialfifoinit1();
RXSerialfifoinit1();
}
uint8_t AvailUSART1(void)
{
if (RXSerialfifolevel1() > 0U)
return 1U;
else
return 0U;
}
uint8_t ReadUSART1(void)
{
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
/* ************* USART2 ***************** */
#if defined(STM32F4_NUCLEO)
volatile uint32_t intcount2;
volatile uint8_t TXSerialfifo2[TX_SERIAL_FIFO_SIZE];
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()
{
uint8_t c;
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);
intcount2++;
}
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)
{
// USART2 - TXD PA2 - RXD PA3
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource2, GPIO_AF_USART2);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource3, GPIO_AF_USART2);
// USART IRQ init
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_Init(&NVIC_InitStructure);
// Configure USART as alternate function
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2 | GPIO_Pin_3; // Tx | Rx
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
// Configure USART baud rate
USART_StructInit(&USART_InitStructure);
USART_InitStructure.USART_BaudRate = speed;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(USART2, &USART_InitStructure);
USART_Cmd(USART2, ENABLE);
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
// initialize the fifos
TXSerialfifoinit2();
RXSerialfifoinit2();
}
uint8_t AvailUSART2(void)
{
if (RXSerialfifolevel2() > 0U)
return 1U;
else
return 0U;
}
uint8_t ReadUSART2(void)
{
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
/* ************* USART3 ***************** */
#if defined(STM32F4_DISCOVERY) || defined(STM32F4_PI)
volatile uint32_t intcount3;
volatile uint8_t TXSerialfifo3[TX_SERIAL_FIFO_SIZE];
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()
{
uint8_t c;
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);
intcount3++;
}
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);
}
}
void InitUSART3(int speed)
{
// USART3 - TXD PC10 - RXD PC11
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource10, GPIO_AF_USART3);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource11, GPIO_AF_USART3);
// USART IRQ init
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_Init(&NVIC_InitStructure);
// Configure USART as alternate function
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11; // Tx | Rx
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOC, &GPIO_InitStructure);
// Configure USART baud rate
USART_StructInit(&USART_InitStructure);
USART_InitStructure.USART_BaudRate = speed;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(USART3, &USART_InitStructure);
USART_Cmd(USART3, ENABLE);
USART_ITConfig(USART3, USART_IT_RXNE, ENABLE);
// initialize the fifos
TXSerialfifoinit3();
RXSerialfifoinit3();
}
uint8_t AvailUSART3(void)
{
if (RXSerialfifolevel3() > 0U)
return 1U;
else
return 0U;
}
uint8_t ReadUSART3(void)
{
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
/* ************* UART5 ***************** */
#if !(defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER))
volatile uint32_t intcount5;
volatile uint8_t TXSerialfifo5[TX_SERIAL_FIFO_SIZE];
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()
{
uint8_t c;
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);
intcount5++;
}
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)
{
// UART5 - TXD PC12 - RXD PD2
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource12, GPIO_AF_UART5);
GPIO_PinAFConfig(GPIOD, GPIO_PinSource2, GPIO_AF_UART5);
// USART IRQ init
NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_Init(&NVIC_InitStructure);
// Configure USART as alternate function
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; // Tx
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; // Rx
GPIO_Init(GPIOD, &GPIO_InitStructure);
// Configure USART baud rate
USART_StructInit(&USART_InitStructure);
USART_InitStructure.USART_BaudRate = speed;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(UART5, &USART_InitStructure);
USART_Cmd(UART5, ENABLE);
USART_ITConfig(UART5, USART_IT_RXNE, ENABLE);
// initialize the fifos
TXSerialfifoinit5();
RXSerialfifoinit5();
}
uint8_t AvailUART5(void)
{
if (RXSerialfifolevel5() > 0U)
return 1U;
else
return 0U;
}
uint8_t ReadUART5(void)
{
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
/////////////////////////////////////////////////////////////////
void CSerialPort::beginInt(uint8_t n, int speed)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
InitUSART3(speed);
#elif defined(STM32F4_PI)
InitUSART1(speed);
#elif defined(STM32F4_NUCLEO)
InitUSART2(speed);
#endif
break;
case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
InitUSART1(speed);
#else
InitUART5(speed);
#endif
break;
default:
break;
}
}
int CSerialPort::availableInt(uint8_t n)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
return AvailUSART3();
#elif defined(STM32F4_PI)
return AvailUSART1();
#elif defined(STM32F4_NUCLEO)
return AvailUSART2();
#endif
case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
return AvailUSART1();
#else
return AvailUART5();
#endif
default:
return false;
}
}
uint8_t CSerialPort::readInt(uint8_t n)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
return ReadUSART3();
#elif defined(STM32F4_PI)
return ReadUSART1();
#elif defined(STM32F4_NUCLEO)
return ReadUSART2();
#endif
case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
return ReadUSART1();
#else
return ReadUART5();
#endif
default:
return 0U;
}
}
void CSerialPort::writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool flush)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
WriteUSART3(data, length);
if (flush)
TXSerialFlush3();
#elif defined(STM32F4_PI)
WriteUSART1(data, length);
if (flush)
TXSerialFlush1();
#elif defined(STM32F4_NUCLEO)
WriteUSART2(data, length);
if (flush)
TXSerialFlush2();
#endif
break;
case 3U:
#if defined(STM32F4_NUCLEO) && defined(STM32F4_NUCLEO_ARDUINO_HEADER)
WriteUSART1(data, length);
if (flush)
TXSerialFlush1();
#else
WriteUART5(data, length);
if (flush)
TXSerialFlush5();
#endif
break;
default:
break;
}
}
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -19,8 +19,9 @@
#if !defined(UTILS_H)
#define UTILS_H
#if defined(__MBED__)
#include "mbed.h"
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#else
#include <Arduino.h>
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -24,13 +24,16 @@ const unsigned int YSF_RADIO_SYMBOL_LENGTH = 5U; // At 24 kHz sample rate
const unsigned int YSF_FRAME_LENGTH_BYTES = 120U;
const unsigned int YSF_FRAME_LENGTH_BITS = YSF_FRAME_LENGTH_BYTES * 8U;
const unsigned int YSF_FRAME_LENGTH_SYMBOLS = YSF_FRAME_LENGTH_BYTES * 4U;
const unsigned int YSF_FRAME_LENGTH_SAMPLES = YSF_FRAME_LENGTH_SYMBOLS * YSF_RADIO_SYMBOL_LENGTH;
const unsigned int YSF_SYNC_LENGTH_BYTES = 5U;
const unsigned int YSF_SYNC_LENGTH_BITS = YSF_SYNC_LENGTH_BYTES * 8U;
const unsigned int YSF_SYNC_LENGTH_SYMBOLS = YSF_SYNC_LENGTH_BYTES * 4U;
const unsigned int YSF_SYNC_LENGTH_SAMPLES = YSF_SYNC_LENGTH_SYMBOLS * YSF_RADIO_SYMBOL_LENGTH;
const unsigned int YSF_FICH_LENGTH_BITS = 200U;
const unsigned int YSF_FICH_LENGTH_SYMBOLS = 100U;
const unsigned int YSF_FICH_LENGTH_SAMPLES = YSF_FICH_LENGTH_SYMBOLS * YSF_RADIO_SYMBOL_LENGTH;
const uint8_t YSF_SYNC_BYTES[] = {0xD4U, 0x71U, 0xC9U, 0x63U, 0x4DU};
const uint8_t YSF_SYNC_BYTES_LENGTH = 5U;
@ -41,6 +44,9 @@ const uint64_t YSF_SYNC_BITS_MASK = 0x000000FFFFFFFFFFU;
// D 4 7 1 C 9 6 3 4 D
// 11 01 01 00 01 11 00 01 11 00 10 01 01 10 00 11 01 00 11 01
// -3 +3 +3 +1 +3 -3 +1 +3 -3 +1 -1 +3 +3 -1 +3 -3 +3 +1 -3 +3
const int8_t YSF_SYNC_SYMBOLS_VALUES[] = {-3, +3, +3, +1, +3, -3, +1, +3, -3, +1, -1, +3, +3, -1, +3, -3, +3, +1, -3, +3};
const uint32_t YSF_SYNC_SYMBOLS = 0x0007B5ADU;
const uint32_t YSF_SYNC_SYMBOLS_MASK = 0x000FFFFFU;

918
YSFRX.cpp

File diff suppressed because it is too large Load Diff

50
YSFRX.h
View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -31,39 +31,39 @@ class CYSFRX {
public:
CYSFRX();
void samples(const q15_t* samples, uint8_t length);
void samples(const q15_t* samples, uint16_t* rssi, uint8_t length);
void reset();
private:
uint32_t m_pll;
bool m_prev;
YSFRX_STATE m_state;
uint32_t m_symbolBuffer;
uint64_t m_bitBuffer;
q15_t m_symbols[YSF_SYNC_LENGTH_SYMBOLS];
uint8_t m_outBuffer[YSF_FRAME_LENGTH_BYTES + 1U];
uint8_t* m_buffer;
uint16_t m_bufferPtr;
uint16_t m_symbolPtr;
uint32_t m_bitBuffer[YSF_RADIO_SYMBOL_LENGTH];
q15_t m_buffer[YSF_FRAME_LENGTH_SAMPLES];
uint16_t m_bitPtr;
uint16_t m_dataPtr;
uint16_t m_startPtr;
uint16_t m_endPtr;
uint16_t m_minSyncPtr;
uint16_t m_maxSyncPtr;
uint16_t m_syncPtr;
q31_t m_maxCorr;
uint16_t m_lostCount;
q15_t m_centre;
q15_t m_threshold;
uint16_t m_metrics1[16U];
uint16_t m_metrics2[16U];
uint16_t* m_oldMetrics;
uint16_t* m_newMetrics;
uint64_t m_decisions[100U];
uint64_t* m_dp;
uint8_t m_countdown;
q15_t m_centre[16U];
q15_t m_centreVal;
q15_t m_threshold[16U];
q15_t m_thresholdVal;
uint8_t m_averagePtr;
uint32_t m_rssiAccum;
uint16_t m_rssiCount;
void processNone(q15_t sample);
void processData(q15_t sample);
bool rxFICH(uint8_t* data, uint8_t* FICH);
void viterbiDecode(uint8_t s0, uint8_t s1);
void chainback(uint8_t* out);
uint32_t getSyndrome23127(uint32_t pattern) const;
uint32_t golay24128(const uint8_t* bytes) const;
bool checksum(const uint8_t* fich) const;
bool correlateSync();
void calculateLevels(uint16_t start, uint16_t count);
void samplesToBits(uint16_t start, uint16_t count, uint8_t* buffer, uint16_t offset, q15_t centre, q15_t threshold);
void writeRSSIData(uint8_t* data);
void writeSamples(uint16_t start, uint8_t control);
};
#endif

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2009-2015 by Jonathan Naylor G4KLX
* Copyright (C) 2009-2016 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -16,35 +16,44 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
// #define WANT_DEBUG
#include "Config.h"
#include "Globals.h"
#include "YSFTX.h"
#include "YSFDefines.h"
#if defined(WIDE_C4FSK_FILTERS_TX)
// Generated using rcosdesign(0.2, 4, 5, 'sqrt') in MATLAB
static q15_t YSF_C4FSK_FILTER[] = {688, -680, -2158, -3060, -2724, -775, 2684, 7041, 11310, 14425, 15565, 14425,
11310, 7041, 2684, -775, -2724, -3060, -2158, -680, 688, 0};
const uint16_t YSF_C4FSK_FILTER_LEN = 22U;
#else
// Generated using rcosdesign(0.2, 8, 5, 'sqrt') in MATLAB
static q15_t YSF_C4FSK_FILTER[] = {401, 104, -340, -731, -847, -553, 112, 909, 1472, 1450, 683, -675, -2144, -3040, -2706, -770, 2667, 6995,
11237, 14331, 15464, 14331, 11237, 6995, 2667, -770, -2706, -3040, -2144, -675, 683, 1450, 1472, 909, 112,
-553, -847, -731, -340, 104, 401, 0};
const uint16_t YSF_C4FSK_FILTER_LEN = 42U;
#endif
const q15_t YSF_LEVELA[] = { 809, 809, 809, 809, 809};
const q15_t YSF_LEVELB[] = { 269, 269, 269, 269, 269};
const q15_t YSF_LEVELC[] = {-269, -269, -269, -269, -269};
const q15_t YSF_LEVELD[] = {-809, -809, -809, -809, -809};
const uint8_t YSF_START_SYNC = 0x77U;
const uint8_t YSF_END_SYNC = 0xFFU;
q15_t YSF_A[] = { 1408, 1408, 1408, 1408, 1408};
q15_t YSF_B[] = { 470, 470, 470, 470, 470};
q15_t YSF_C[] = { -470, -470, -470, -470, -470};
q15_t YSF_D[] = {-1408, -1408, -1408, -1408, -1408};
CYSFTX::CYSFTX() :
m_buffer(),
m_buffer(1500U),
m_modFilter(),
m_modState(),
m_poBuffer(),
m_poLen(0U),
m_poPtr(0U),
m_txDelay(120U) // 100ms
m_txDelay(240U), // 200ms
m_count(0U)
{
::memset(m_modState, 0x00U, 70U * sizeof(q15_t));
@ -60,6 +69,8 @@ void CYSFTX::process()
if (m_poLen == 0U) {
if (!m_tx) {
m_count = 0U;
for (uint16_t i = 0U; i < m_txDelay; i++)
m_poBuffer[m_poLen++] = YSF_START_SYNC;
} else {
@ -75,7 +86,7 @@ void CYSFTX::process()
if (m_poLen > 0U) {
uint16_t space = io.getSpace();
while (space > (4U * YSF_RADIO_SYMBOL_LENGTH) && space < 1000U) {
while (space > (4U * YSF_RADIO_SYMBOL_LENGTH)) {
uint8_t c = m_poBuffer[m_poPtr++];
writeByte(c);
@ -107,8 +118,8 @@ uint8_t CYSFTX::writeData(const uint8_t* data, uint8_t length)
void CYSFTX::writeByte(uint8_t c)
{
q15_t inBuffer[YSF_RADIO_SYMBOL_LENGTH * 4U];
q15_t outBuffer[YSF_RADIO_SYMBOL_LENGTH * 4U];
q15_t inBuffer[YSF_RADIO_SYMBOL_LENGTH * 4U + 1U];
q15_t outBuffer[YSF_RADIO_SYMBOL_LENGTH * 4U + 1U];
const uint8_t MASK = 0xC0U;
@ -116,28 +127,46 @@ void CYSFTX::writeByte(uint8_t c)
for (uint8_t i = 0U; i < 4U; i++, c <<= 2, p += YSF_RADIO_SYMBOL_LENGTH) {
switch (c & MASK) {
case 0xC0U:
::memcpy(p, YSF_A, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, YSF_LEVELA, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x80U:
::memcpy(p, YSF_B, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, YSF_LEVELB, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
case 0x00U:
::memcpy(p, YSF_C, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, YSF_LEVELC, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
default:
::memcpy(p, YSF_D, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
::memcpy(p, YSF_LEVELD, YSF_RADIO_SYMBOL_LENGTH * sizeof(q15_t));
break;
}
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, YSF_RADIO_SYMBOL_LENGTH * 4U);
uint16_t blockSize = YSF_RADIO_SYMBOL_LENGTH * 4U;
io.write(outBuffer, YSF_RADIO_SYMBOL_LENGTH * 4U);
// Handle the case of the oscillator not being accurate enough
if (m_sampleCount > 0U) {
m_count += YSF_RADIO_SYMBOL_LENGTH * 4U;
if (m_count >= m_sampleCount) {
if (m_sampleInsert) {
inBuffer[YSF_RADIO_SYMBOL_LENGTH * 4U] = inBuffer[YSF_RADIO_SYMBOL_LENGTH * 4U - 1U];
blockSize++;
} else {
blockSize--;
}
m_count -= m_sampleCount;
}
}
::arm_fir_fast_q15(&m_modFilter, inBuffer, outBuffer, blockSize);
io.write(STATE_YSF, outBuffer, blockSize);
}
void CYSFTX::setTXDelay(uint8_t delay)
{
m_txDelay = 120U + uint16_t(delay) * 12U; // 100ms + tx delay
m_txDelay = 600U + uint16_t(delay) * 12U; // 500ms + tx delay
}
uint16_t CYSFTX::getSpace() const

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2015 by Jonathan Naylor G4KLX
* Copyright (C) 2015,2016,2017 by Jonathan Naylor G4KLX
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -39,10 +39,11 @@ private:
CSerialRB m_buffer;
arm_fir_instance_q15 m_modFilter;
q15_t m_modState[70U]; // NoTaps + BlockSize - 1, 42 + 20 - 1 plus some spare
uint8_t m_poBuffer[720U];
uint8_t m_poBuffer[1200U];
uint16_t m_poLen;
uint16_t m_poPtr;
uint16_t m_txDelay;
uint32_t m_count;
void writeByte(uint8_t c);
};

98
mmdvmmenu.sh Executable file
View File

@ -0,0 +1,98 @@
#!/bin/bash
###############################################################################
#
# mmdvmmenu.sh
#
# Copyright (C) 2016 by Paul Nannery KC2VRJ
#
# 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.
#
###############################################################################
#
# On a Linux based system, such as a Raspberry Pi, this script will perform
# Modification of the Config.h file for most options. It makes a Back up when
# you start the script if none is present. You must recompile and load firmware
# onto the Arduino Due if changes are made.
#
###############################################################################
#
# CONFIGURATION
#
# Location of Config.h
conf=Config.h
#Location of backup file
confbak=Config.h.bak
################################################################################
#
# Do not edit below here
#
###############################################################################
# Check for backup file and make one if not present
if [ ! -f $confbak ];then
cp -f $conf $confbak
fi
while :
do
clear
cat<<EOF
==============================================================
MMDVM Configuration Options
--------------------------------------------------------------
Please enter your choice:
(1) Enable 12.000 MHZ Clock
(2) Enable 12.288 MHZ Clock
(3) Enable 14.400 MHz Clock
(4) Enable 19.200 MHz Clock
(5) Use the COS to lockout the modem
(6) Use pins to output the current mode
(7) Use layout for the PAPA board
(8) Use layout for ZUM V1.0 and V1.0.1 boards
(9) Use layout for SP8NTH board
(0) Use modem as display driver
(A) Return to Default
(Q)uit
---------------------------------------------------------------
EOF
read -n1 -s
case "$REPLY" in
"1") sed -e 's/\/\/ #define EXTERNAL_OSC 12000000/#define EXTERNAL_OSC 12000000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "12.000 MHz clock enabled";;
"2") sed -e 's/\/\/ #define EXTERNAL_OSC 12288000/#define EXTERNAL_OSC 12288000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "12.288 MHz clock enabled";;
"3") sed -e 's/\/\/ #define EXTERNAL_OSC 14400000/#define EXTERNAL_OSC 14400000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "14.400 MHz clock enabled";;
"4") sed -e 's/\/\/ #define EXTERNAL_OSC 19200000/#define EXTERNAL_OSC 19200000/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "19.200 MHz clock enabled";;
"5") sed -e 's/\/\/ #define USE_COS_AS_LOCKOUT /#define USE_COS_AS_LOCKOUT/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "COS as Lockout enabled";;
"6") sed -e 's/\/\/ #define ARDUINO_MODE_PINS/#define ARDUINO_MODE_PINS/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Mode pins enabled";;
"7") sed -e 's/\/\/ #define ARDUINO_DUE_PAPA/#define ARDUINO_DUE_PAPA/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Layout for the PAPA board enabled";;
"8") sed -e 's/\/\/ #define ARDUINO_DUE_ZUM_V10/#define ARDUINO_DUE_ZUM_V10/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Layout for ZUM V1.0 and V1.0.1 boards enabled";;
"9") sed -e 's/\/\/ #define ARDUINO_DUE_NTH/#define ARDUINO_DUE_NTH/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Layout for SP8NTH board enabled";;
"0") sed -e 's/\/\/ #define SERIAL_REPEATER/#define SERIAL_REPEATER/' $conf > $conf.tmp && mv -f $conf.tmp $conf && echo "Modem display driver enabled";;
"A") mv -f $confbak $conf ;;
"a") mv -f $confbak $conf ;;
"Q") echo "If any changes are made you need to (re-)upload the firmware to MMDVM" && exit;;
"q") echo "If any changes are made you need to (re-)upload the firmware to MMDVM" && exit;;
* ) echo "invalid option" ;;
esac
sleep 1
done

138
stm32f4xx_link.ld Normal file
View File

@ -0,0 +1,138 @@
/*
* Copyright (C) 2016 by Andy Uribe CA6JAU
*
* 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.
*/
/* Required amount of heap and stack */
_min_heap_size = 0x1000;
_min_stack_size = 0x0800;
/* The entry point in the interrupt vector table */
ENTRY(Reset_Handler)
/* Memory areas */
MEMORY
{
ROM (rx) : ORIGIN = 0x08000000, LENGTH = 1024K /* FLASH */
CCMRAM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K /* Core Coupled Memory (CPU only access) */
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K /* Main RAM (bus matrix)*/
}
/* Stack start address (end of 128K RAM) */
_estack = ORIGIN(RAM) + LENGTH(RAM);
SECTIONS
{
.text :
{
/* The interrupt vector table */
. = ALIGN(4);
KEEP(*(.isr_vector .isr_vector.*))
/* The program code */
. = ALIGN(4);
*(.text .text*)
*(.rodata .rodata*)
/* ARM-Thumb code */
*(.glue_7) *(.glue_7t)
. = ALIGN(4);
KEEP(*(.init))
KEEP(*(.fini))
/* EABI C++ global constructors support */
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
/* EABI C++ global constructors support */
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
/* EABI C++ global constructors support */
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
} > ROM
/* ARM sections containing exception unwinding information */
.ARM.extab : {
__extab_start = .;
*(.ARM.extab* .gnu.linkonce.armextab.*)
__extab_end = .;
} > ROM
/* ARM index entries for section unwinding */
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} > ROM
/* Start address for the initialization values of the .data section */
_sidata = .;
/* The .data section (initialized data) */
.data : AT ( _sidata )
{
. = ALIGN(4);
_sdata = . ; /* Start address for the .data section */
*(.data .data*)
. = ALIGN(4);
_edata = . ; /* End address for the .data section */
} > RAM
/* The .bss section (uninitialized data) */
.bss :
{
. = ALIGN(4);
_sbss = .; /* Start address for the .bss section */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = . ; /* End address for the .bss section */
__bss_end__ = _ebss;
} > RAM
/* Space for heap and stack */
.heap_stack :
{
end = . ; /* 'end' symbol defines heap location */
_end = end ;
. = . + _min_heap_size; /* Additional space for heap and stack */
. = . + _min_stack_size;
} > RAM
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
}