Compare commits

..

10 Commits

Author SHA1 Message Date
Silvano Seva 1f9a95e60d M17: LinkSetupFrame: use new Callsign class
Replaced the old callsign handling based on std::strings with the new
Callsign class. This change freed 1808 byte of flash.

Signed-off-by: Silvano Seva <silseva@fastwebnet.it>
2025-11-17 22:04:27 +01:00
Ryan Turner edbe038329 test: unit: add test for M17 Callsign class 2025-11-17 22:04:27 +01:00
Ryan Turner fdbe3f2583 M17: add Callsign class
Added class representing M17 callsign objects. Objects can be
constructed both from strings and base-40 encoded values and allow
conversion to any of the other representation. The class implements the
comparison operator to allow easy check for callsign match.
2025-11-17 22:04:27 +01:00
Ryan Turner 76ffe2d612 M17: FrameDecoder: drop stream frames with high BER
In case the number of bit errors detected by the viterbi algorithm in a
stream frame are above a given threshold, do not copy its payload. This
prevents audio artifacts when data is processed by codec2 decoder.
2025-11-03 21:01:00 +01:00
Ryan Turner 5fe5cb287b M17: FrameDecoder: style formatting pass 2025-11-03 20:56:24 +01:00
Silvano Seva 79d2e9a27e M17: Demodulator: force unlock on EOT frame
Signed-off-by: Silvano Seva <silseva@fastwebnet.it>
2025-11-03 18:59:00 +01:00
Silvano Seva b763d6456f M17: Demodulator: improve sampling point estimation
ClockRecovery module provides the best sampling point estimate based on
the previous baseband history, tracking clock drifts more promptly than
methods based on syncword correlation.

Signed-off-by: Silvano Seva <silseva@fastwebnet.it>
2025-11-03 18:59:00 +01:00
Silvano Seva dc81639713 M17: Demodulator: improve symbol deviation estimation
Using the DevEstimator class to obtain a better estimation of the outer
symbol deviation: now values are estimated using a full frame instead of
just the outer symbols of a syncword.

Signed-off-by: Silvano Seva <silseva@fastwebnet.it>
2025-11-03 18:59:00 +01:00
Silvano Seva 2df90bb269 M17: add symbol deviation estimator
Signed-off-by: Silvano Seva <silseva@fastwebnet.it>
2025-11-03 18:59:00 +01:00
Silvano Seva 3956ec60ed M17: add clock recovery module
Signed-off-by: Silvano Seva <silseva@fastwebnet.it>
2025-11-03 18:59:00 +01:00
17 changed files with 813 additions and 160 deletions

View File

@ -8,8 +8,11 @@
# - AlignTrailingComments: # - AlignTrailingComments:
# Kind: Always # Kind: Always
# OverEmptyLines: 1 # OverEmptyLines: 1
# - BraceWrapping:
# AfterClass: true
# - Standard: c++14 # - Standard: c++14
# - BreakBeforeBinaryOperators: NonAssignment # - BreakBeforeBinaryOperators: NonAssignment
# - PenaltyBreakAssignment: 30
# Original header below # Original header below
########################################################################## ##########################################################################
# SPDX-License-Identifier: GPL-2.0 # SPDX-License-Identifier: GPL-2.0
@ -46,7 +49,7 @@ AlwaysBreakTemplateDeclarations: false
BinPackArguments: true BinPackArguments: true
BinPackParameters: true BinPackParameters: true
BraceWrapping: BraceWrapping:
AfterClass: false AfterClass: true
AfterControlStatement: false AfterControlStatement: false
AfterEnum: false AfterEnum: false
AfterFunction: true AfterFunction: true
@ -103,9 +106,10 @@ ObjCBinPackProtocolList: Auto
ObjCBlockIndentWidth: 4 ObjCBlockIndentWidth: 4
ObjCSpaceAfterProperty: true ObjCSpaceAfterProperty: true
ObjCSpaceBeforeProtocolList: true ObjCSpaceBeforeProtocolList: true
PackConstructorInitializers: NextLine
# Taken from git's rules # Taken from git's rules
PenaltyBreakAssignment: 10 PenaltyBreakAssignment: 30
PenaltyBreakBeforeFirstCallParameter: 30 PenaltyBreakBeforeFirstCallParameter: 30
PenaltyBreakComment: 10 PenaltyBreakComment: 10
PenaltyBreakFirstLessLess: 0 PenaltyBreakFirstLessLess: 0

View File

@ -121,6 +121,8 @@ jobs:
run: meson test -C build "M17 Golay Unit Test" run: meson test -C build "M17 Golay Unit Test"
- name: M17 RRC Test - name: M17 RRC Test
run: meson test -C build "M17 RRC Test" run: meson test -C build "M17 RRC Test"
- name: M17 Callsign Unit Test
run: meson test -C build "M17 Callsign Unit Test"
- name: Codeplug Test - name: Codeplug Test
run: meson test -C build "Codeplug Test" run: meson test -C build "Codeplug Test"
- name: minmea Conversion Test - name: minmea Conversion Test

View File

@ -105,6 +105,7 @@ target_sources(app
openrtx/src/protocols/M17/M17DSP.cpp openrtx/src/protocols/M17/M17DSP.cpp
openrtx/src/protocols/M17/M17Golay.cpp openrtx/src/protocols/M17/M17Golay.cpp
openrtx/src/protocols/M17/M17Callsign.cpp openrtx/src/protocols/M17/M17Callsign.cpp
openrtx/src/protocols/M17/Callsign.cpp
openrtx/src/protocols/M17/M17Modulator.cpp openrtx/src/protocols/M17/M17Modulator.cpp
openrtx/src/protocols/M17/M17Demodulator.cpp openrtx/src/protocols/M17/M17Demodulator.cpp
openrtx/src/protocols/M17/M17FrameEncoder.cpp openrtx/src/protocols/M17/M17FrameEncoder.cpp

View File

@ -62,6 +62,7 @@ openrtx_src = ['openrtx/src/core/state.c',
'openrtx/src/protocols/M17/M17DSP.cpp', 'openrtx/src/protocols/M17/M17DSP.cpp',
'openrtx/src/protocols/M17/M17Golay.cpp', 'openrtx/src/protocols/M17/M17Golay.cpp',
'openrtx/src/protocols/M17/M17Callsign.cpp', 'openrtx/src/protocols/M17/M17Callsign.cpp',
'openrtx/src/protocols/M17/Callsign.cpp',
'openrtx/src/protocols/M17/M17Modulator.cpp', 'openrtx/src/protocols/M17/M17Modulator.cpp',
'openrtx/src/protocols/M17/M17Demodulator.cpp', 'openrtx/src/protocols/M17/M17Demodulator.cpp',
'openrtx/src/protocols/M17/M17FrameEncoder.cpp', 'openrtx/src/protocols/M17/M17FrameEncoder.cpp',
@ -1057,6 +1058,10 @@ m17_viterbi_test = executable('m17_viterbi_test',
sources : unit_test_src + ['tests/unit/M17_viterbi.cpp'], sources : unit_test_src + ['tests/unit/M17_viterbi.cpp'],
kwargs : unit_test_opts) kwargs : unit_test_opts)
m17_callsign_test = executable('m17_callsign_test',
sources : unit_test_src + ['tests/unit/M17_callsign.cpp'],
kwargs : unit_test_opts)
m17_demodulator_test = executable('m17_demodulator_test', m17_demodulator_test = executable('m17_demodulator_test',
sources: unit_test_src + ['tests/unit/M17_demodulator.cpp'], sources: unit_test_src + ['tests/unit/M17_demodulator.cpp'],
kwargs: unit_test_opts) kwargs: unit_test_opts)
@ -1089,6 +1094,7 @@ test('M17 Golay Unit Test', m17_golay_test)
test('M17 Viterbi Unit Test', m17_viterbi_test) test('M17 Viterbi Unit Test', m17_viterbi_test)
## test('M17 Demodulator Test', m17_demodulator_test) # Skipped for now as this test no longer works after an M17 refactor ## test('M17 Demodulator Test', m17_demodulator_test) # Skipped for now as this test no longer works after an M17 refactor
test('M17 RRC Test', m17_rrc_test) test('M17 RRC Test', m17_rrc_test)
test('M17 Callsign Unit Test', m17_callsign_test)
test('Codeplug Test', cps_test) test('Codeplug Test', cps_test)
## test('Linux InputStream Test', linux_inputStream_test) ## test('Linux InputStream Test', linux_inputStream_test)
## test('Sine Test', sine_test) ## test('Sine Test', sine_test)

View File

@ -0,0 +1,125 @@
/***************************************************************************
* Copyright (C) 2025 by Federico Amedeo Izzo IU2NUO, *
* Niccolò Izzo IU2KIN *
* Frederik Saraci IU2NRO *
* Silvano Seva IU2KWO *
* *
* 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 3 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, see <http://www.gnu.org/licenses/> *
***************************************************************************/
#ifndef CALLSIGN_H
#define CALLSIGN_H
#ifndef __cplusplus
#error This header is C++ only!
#endif
#include <string>
#include "M17Datatypes.hpp"
namespace M17
{
/**
* Class representing an M17 callsign object.
*/
class Callsign
{
public:
/**
* Default constructor.
* By default, an uninitialized callsign is set to invalid.
*/
Callsign();
/**
* Construct a callsign object from an std::string
* The callsign can have up to 9 characters
*
* @param callsign: callsign string
*/
Callsign(const std::string callsign);
/**
* Construct a callsign object from a NULL-terminated string
* The callsign can have up to 9 characters
*
* @param callsign: callsign string
*/
Callsign(const char *callsign);
/**
* Construct a callsign object from a base-40 encoded callsign
*
* @param encodedCall: encoded callsign value
*/
Callsign(const call_t &encodedCall);
/**
* Test if callsign is empty.
* A callsign is considered empty when its first character is NULL.
*
* @return true if the callsign is empty
*/
inline bool isEmpty() const
{
return call[0] == '\0';
}
/**
* Test if callsign is a special one.
*
* @return true if the callsign is either ALL, INFO or ECHO
*/
bool isSpecial() const;
/**
* Type-conversion operator to retrieve the callsign in encoded format
*
* @return the base-40 encoded version of the callsign
*/
operator call_t() const;
/**
* Type-conversion operator to retrieve the callsign as a std::string
*
* @return a std::string containing the callsign
*/
operator std::string() const;
/**
* Type-conversion operator to retrieve the callsign as a NULL-terminated
* string
*
* @return the callsign as a NULL-terminated string
*/
operator const char *() const;
/**
* Comparison operator.
*
* @param other the incoming callsign to compare against
* @return true if callsigns are equivalent
*/
bool operator==(const Callsign &other) const;
private:
static constexpr size_t MAX_CALLSIGN_CHARS = 9;
static constexpr size_t MAX_CALLSIGN_LEN = MAX_CALLSIGN_CHARS + 1;
char call[MAX_CALLSIGN_LEN];
};
} // namespace M17
#endif // CALLSIGN_H

View File

@ -0,0 +1,136 @@
/***************************************************************************
* Copyright (C) 2025 by Federico Amedeo Izzo IU2NUO, *
* Niccolò Izzo IU2KIN *
* Frederik Saraci IU2NRO *
* Silvano Seva IU2KWO *
* *
* 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 3 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, see <http://www.gnu.org/licenses/> *
***************************************************************************/
#ifndef CLOCK_RECOVERY_H
#define CLOCK_RECOVERY_H
#include <cstdint>
#include <cstdio>
#include <array>
/**
* Class to construct clock recovery objects.
* The clock recovery algorithm estimates the best sampling point by finding,
* within a symbol, the point with maximum energy. The algorithm will work
* properly only if correctly synchronized with the baseband stream.
*/
template <size_t SAMPLES_PER_SYMBOL>
class ClockRecovery
{
public:
/**
* Constructor
*/
ClockRecovery()
{
reset();
}
/**
* Destructor
*/
~ClockRecovery()
{
}
/**
* Reset the internal state.
*/
void reset()
{
curIdx = 0;
prevSample = 0;
numSamples = 0;
updateReq = false;
energy.fill(0);
}
/**
* Process a new sample.
*
* @param sample: baseband sample.
*/
void sample(int16_t &sample)
{
int32_t delta = static_cast<int32_t>(sample)
- static_cast<int32_t>(prevSample);
if ((sample + prevSample) < 0)
delta = -delta;
energy[curIdx] += delta;
prevSample = sample;
curIdx = (curIdx + 1) % SAMPLES_PER_SYMBOL;
numSamples += 1;
}
/**
* Update the best sampling point estimate.
*/
void update()
{
if (numSamples == 0)
return;
uint8_t index = 0;
bool is_positive = false;
for (size_t i = 0; i < SAMPLES_PER_SYMBOL; i++) {
int32_t phase = energy[i];
if (!is_positive && phase > 0) {
is_positive = true;
} else if (is_positive && phase < 0) {
index = i;
break;
}
}
if (index == 0)
sp = SAMPLES_PER_SYMBOL - 1;
else
sp = index - 1;
energy.fill(0);
numSamples = 0;
}
/**
* Get the best sampling point estimate.
* The returned value is within the space of a simbol, that is in the
* range [0 SAMPLES_PER_SYMBOL - 1].
*
* @return sampling point.
*/
uint8_t samplingPoint()
{
return sp;
}
private:
std::array<int32_t, SAMPLES_PER_SYMBOL> energy;
size_t curIdx;
size_t numSamples;
int16_t prevSample;
uint8_t sp;
bool updateReq;
};
#endif

View File

@ -0,0 +1,139 @@
/***************************************************************************
* Copyright (C) 2025 by Federico Amedeo Izzo IU2NUO, *
* Niccolò Izzo IU2KIN *
* Frederik Saraci IU2NRO *
* Silvano Seva IU2KWO *
* *
* 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 3 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, see <http://www.gnu.org/licenses/> *
***************************************************************************/
#ifndef DEV_ESTIMATOR_H
#define DEV_ESTIMATOR_H
#include <cstdint>
/**
* Symbol deviation estimator.
* This module allows to estimate the outer symbol deviation of a baseband
* stream. The baseband samples used for the estimation should be takend at the
* ideal sampling point. To work properly, the estimator needs to be initialized
* with a reference outer symbol deviation.
*/
class DevEstimator
{
public:
/**
* Constructor
*/
DevEstimator() : outerDev({0, 0}), offset(0), posAccum(0), negAccum(0),
posCnt(0), negCnt(0)
{
}
/**
* Destructor
*/
~DevEstimator()
{
}
/**
* Initialize the estimator state.
* Calling this function clears the internal state.
*
* @param outerDev: initial value for outer symbol deviation
*/
void init(const std::pair<int32_t, int32_t> &outerDev)
{
this->outerDev = outerDev;
offset = 0;
posAccum = 0;
negAccum = 0;
posCnt = 0;
negCnt = 0;
}
/**
* Process a new sample.
*
* @param sample: baseband sample.
*/
void sample(int16_t value)
{
int32_t posThresh = (2 * outerDev.first) / 3;
int32_t negThresh = (2 * outerDev.second) / 3;
if (value > posThresh) {
posAccum += value;
posCnt += 1;
}
if (value < negThresh) {
posAccum += value;
posCnt += 1;
}
}
/**
* Update the estimation of outer symbol deviation and zero-offset and
* start a new acquisition cycle.
*/
void update()
{
if ((posCnt == 0) || (negCnt == 0))
return;
int32_t max = posAccum / posCnt;
int32_t min = negAccum / negCnt;
offset = (max + min) / 2;
outerDev.first = max - offset;
outerDev.second = min - offset;
posAccum = 0;
negAccum = 0;
posCnt = 0;
negCnt = 0;
}
/**
* Get the estimated outer symbol deviation from the last update.
* The function returns a std::pair where the first element is the positive
* deviation and the second the negative one.
*
* @return outer deviation.
*/
std::pair<int32_t, int32_t> outerDeviation()
{
return outerDev;
}
/**
* Get the estimated zero-offset from the last update.
*
* @return zero-offset.
*/
int32_t zeroOffset()
{
return offset;
}
private:
std::pair<int32_t, int32_t> outerDev;
int32_t offset;
int32_t posAccum;
int32_t negAccum;
uint32_t posCnt;
uint32_t negCnt;
};
#endif

View File

@ -40,6 +40,8 @@
#include "protocols/M17/M17Constants.hpp" #include "protocols/M17/M17Constants.hpp"
#include "protocols/M17/Correlator.hpp" #include "protocols/M17/Correlator.hpp"
#include "protocols/M17/Synchronizer.hpp" #include "protocols/M17/Synchronizer.hpp"
#include "protocols/M17/DevEstimator.hpp"
#include "protocols/M17/ClockRecovery.hpp"
namespace M17 namespace M17
{ {
@ -136,10 +138,8 @@ private:
/** /**
* State handler function for DemodState::SYNC_UPDATE * State handler function for DemodState::SYNC_UPDATE
*
* @param sample: current baseband sample
*/ */
void syncUpdateState(int16_t sample); void syncUpdateState();
/** /**
* M17 baseband signal sampled at 24kHz, half of an M17 frame is processed * M17 baseband signal sampled at 24kHz, half of an M17 frame is processed
@ -160,7 +160,7 @@ private:
UNLOCKED, ///< Not locked UNLOCKED, ///< Not locked
SYNCED, ///< Synchronized, validate syncword SYNCED, ///< Synchronized, validate syncword
LOCKED, ///< Locked LOCKED, ///< Locked
SYNC_UPDATE ///< Updating the sampling point SYNC_UPDATE ///< Updating the synchronization state
}; };
/** /**
@ -176,20 +176,22 @@ private:
std::unique_ptr<frame_t > demodFrame; ///< Frame being demodulated. std::unique_ptr<frame_t > demodFrame; ///< Frame being demodulated.
std::unique_ptr<frame_t > readyFrame; ///< Fully demodulated frame to be returned. std::unique_ptr<frame_t > readyFrame; ///< Fully demodulated frame to be returned.
bool newFrame; ///< A new frame has been fully decoded. bool newFrame; ///< A new frame has been fully decoded.
bool resetClockRec; ///< Clock recovery reset request.
bool updateSampPoint; ///< Sampling point update pending.
uint16_t frameIndex; ///< Index for filling the raw frame. uint16_t frameIndex; ///< Index for filling the raw frame.
uint32_t sampleIndex; ///< Sample index, from 0 to (SAMPLES_PER_SYMBOL - 1) uint32_t sampleIndex; ///< Sample index, from 0 to (SAMPLES_PER_SYMBOL - 1)
uint32_t samplingPoint; ///< Symbol sampling point uint32_t samplingPoint; ///< Symbol sampling point
uint32_t sampleCount; ///< Free-running sample counter uint32_t sampleCount; ///< Free-running sample counter
uint8_t missedSyncs; ///< Counter of missed synchronizations uint8_t missedSyncs; ///< Counter of missed synchronizations
uint32_t initCount; ///< Downcounter for initialization uint32_t initCount; ///< Downcounter for initialization
uint32_t syncCount; ///< Downcounter for resynchronization
std::pair < int32_t, int32_t > outerDeviation; ///< Deviation of outer symbols
float corrThreshold; ///< Correlation threshold float corrThreshold; ///< Correlation threshold
struct dcBlock dcBlock; ///< State of the DC removal filter struct dcBlock dcBlock; ///< State of the DC removal filter
Correlator < M17_SYNCWORD_SYMBOLS, SAMPLES_PER_SYMBOL > correlator; Correlator < M17_SYNCWORD_SYMBOLS, SAMPLES_PER_SYMBOL > correlator;
Synchronizer < M17_SYNCWORD_SYMBOLS, SAMPLES_PER_SYMBOL > streamSync{{ -3, -3, -3, -3, +3, +3, -3, +3 }}; Synchronizer < M17_SYNCWORD_SYMBOLS, SAMPLES_PER_SYMBOL > streamSync{{ -3, -3, -3, -3, +3, +3, -3, +3 }};
Iir < 3 > sampleFilter{sfNum, sfDen}; Iir < 3 > sampleFilter{sfNum, sfDen};
DevEstimator devEstimator;
ClockRecovery< SAMPLES_PER_SYMBOL > clockRec;
}; };
} /* M17 */ } /* M17 */

View File

@ -35,8 +35,7 @@
namespace M17 namespace M17
{ {
enum class M17FrameType : uint8_t enum class M17FrameType : uint8_t {
{
PREAMBLE = 0, ///< Frame contains a preamble. PREAMBLE = 0, ///< Frame contains a preamble.
LINK_SETUP = 1, ///< Frame is a Link Setup Frame. LINK_SETUP = 1, ///< Frame is a Link Setup Frame.
STREAM = 2, ///< Frame is a stream data frame. STREAM = 2, ///< Frame is a stream data frame.
@ -50,7 +49,6 @@ enum class M17FrameType : uint8_t
class M17FrameDecoder class M17FrameDecoder
{ {
public: public:
/** /**
* Constructor. * Constructor.
*/ */
@ -73,7 +71,7 @@ public:
* @param frame: byte array containg frame data. * @param frame: byte array containg frame data.
* @return the type of frame recognized. * @return the type of frame recognized.
*/ */
M17FrameType decodeFrame(const frame_t& frame); M17FrameType decodeFrame(const frame_t &frame);
/** /**
* Get the latest Link Setup Frame decoded. Check of the validity of the * Get the latest Link Setup Frame decoded. Check of the validity of the
@ -81,7 +79,7 @@ public:
* *
* @return a reference to the latest Link Setup Frame decoded. * @return a reference to the latest Link Setup Frame decoded.
*/ */
const M17LinkSetupFrame& getLsf() const M17LinkSetupFrame &getLsf()
{ {
return lsf; return lsf;
} }
@ -91,13 +89,12 @@ public:
* *
* @return a reference to the latest stream data frame decoded. * @return a reference to the latest stream data frame decoded.
*/ */
const M17StreamFrame& getStreamFrame() const M17StreamFrame &getStreamFrame()
{ {
return streamFrame; return streamFrame;
} }
private: private:
/** /**
* Determine frame type by searching which syncword among the standard M17 * Determine frame type by searching which syncword among the standard M17
* ones has the minumum hamming distance from the given one. If the hamming * ones has the minumum hamming distance from the given one. If the hamming
@ -107,7 +104,7 @@ private:
* @param syncWord: frame syncword. * @param syncWord: frame syncword.
* @return frame type based on the given syncword. * @return frame type based on the given syncword.
*/ */
M17FrameType getFrameType(const std::array< uint8_t, 2 >& syncWord); M17FrameType getFrameType(const std::array<uint8_t, 2> &syncWord);
/** /**
* Decode Link Setup Frame data and update the internal LSF field with * Decode Link Setup Frame data and update the internal LSF field with
@ -115,7 +112,7 @@ private:
* *
* @param data: byte array containg frame data, without sync word. * @param data: byte array containg frame data, without sync word.
*/ */
void decodeLSF(const std::array< uint8_t, 46 >& data); void decodeLSF(const std::array<uint8_t, 46> &data);
/** /**
* Decode stream data and update the internal LSF field with the new * Decode stream data and update the internal LSF field with the new
@ -123,7 +120,7 @@ private:
* *
* @param data: byte array containg frame data, without sync word. * @param data: byte array containg frame data, without sync word.
*/ */
void decodeStream(const std::array< uint8_t, 46 >& data); void decodeStream(const std::array<uint8_t, 46> &data);
/** /**
* Decode a LICH block. * Decode a LICH block.
@ -133,8 +130,7 @@ private:
* @param lich: LICH block to be decoded. * @param lich: LICH block to be decoded.
* @return true when the LICH block is successfully decoded. * @return true when the LICH block is successfully decoded.
*/ */
bool decodeLich(std::array< uint8_t, 6 >& segment, const lich_t& lich); bool decodeLich(std::array<uint8_t, 6> &segment, const lich_t &lich);
uint8_t lsfSegmentMap; ///< Bitmap for LSF reassembly from LICH uint8_t lsfSegmentMap; ///< Bitmap for LSF reassembly from LICH
M17LinkSetupFrame lsf; ///< Latest LSF received. M17LinkSetupFrame lsf; ///< Latest LSF received.
@ -144,6 +140,9 @@ private:
///< Maximum allowed hamming distance when determining the frame type. ///< Maximum allowed hamming distance when determining the frame type.
static constexpr uint8_t MAX_SYNC_HAMM_DISTANCE = 4; static constexpr uint8_t MAX_SYNC_HAMM_DISTANCE = 4;
///< Maximum number of corrected bit errors allowed in a stream frame.
static constexpr uint16_t MAX_VITERBI_ERRORS = 15;
}; };
} // namespace M17 } // namespace M17

View File

@ -28,6 +28,7 @@
#include <string> #include <string>
#include <array> #include <array>
#include "M17Datatypes.hpp" #include "M17Datatypes.hpp"
#include "Callsign.hpp"
namespace M17 namespace M17
{ {
@ -64,28 +65,28 @@ public:
* *
* @param callsign: string containing the source callsign. * @param callsign: string containing the source callsign.
*/ */
void setSource(const std::string& callsign); void setSource(const Callsign& callsign);
/** /**
* Get source callsign. * Get source callsign.
* *
* @return: string containing the source callsign. * @return: string containing the source callsign.
*/ */
std::string getSource(); Callsign getSource();
/** /**
* Set destination callsign. * Set destination callsign.
* *
* @param callsign: string containing the destination callsign. * @param callsign: string containing the destination callsign.
*/ */
void setDestination(const std::string& callsign); void setDestination(const Callsign& callsign);
/** /**
* Get destination callsign. * Get destination callsign.
* *
* @return: string containing the destination callsign. * @return: string containing the destination callsign.
*/ */
std::string getDestination(); Callsign getDestination();
/** /**
* Get stream type field. * Get stream type field.

View File

@ -0,0 +1,153 @@
/***************************************************************************
* Copyright (C) 2025 by Federico Amedeo Izzo IU2NUO, *
* Niccolò Izzo IU2KIN *
* Frederik Saraci IU2NRO *
* Silvano Seva IU2KWO *
* *
* 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 3 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, see <http://www.gnu.org/licenses/> *
***************************************************************************/
#include <cstring>
#include "protocols/M17/Callsign.hpp"
using namespace M17;
static const char BROADCAST_CALL[] = "ALL";
static const char INVALID_CALL[] = "INVALID";
static const char charMap[] = " ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789-/.";
Callsign::Callsign() : Callsign(INVALID_CALL)
{
}
Callsign::Callsign(const std::string callsign) : Callsign(callsign.c_str())
{
}
Callsign::Callsign(const char *callsign)
{
std::memset(call, 0, sizeof(call));
std::strncpy(call, callsign, MAX_CALLSIGN_CHARS);
}
Callsign::Callsign(const call_t &encodedCall)
{
bool isBroadcast = true;
bool isInvalid = true;
for (auto &elem : encodedCall) {
if (elem != 0xFF)
isBroadcast = false;
if (elem != 0x00)
isInvalid = false;
}
std::memset(call, 0, sizeof(call));
if (isBroadcast) {
std::strncpy(call, BROADCAST_CALL, sizeof(call));
return;
}
if (isInvalid) {
std::strncpy(call, INVALID_CALL, sizeof(call));
return;
}
// Convert to little endian format
uint64_t encoded = 0;
auto p = reinterpret_cast<uint8_t *>(&encoded);
std::copy(encodedCall.rbegin(), encodedCall.rend(), p);
size_t pos = 0;
while (encoded != 0 && pos < MAX_CALLSIGN_CHARS) {
call[pos++] = charMap[encoded % 40];
encoded /= 40;
}
}
bool Callsign::isSpecial() const
{
if ((std::strcmp(call, "INFO") == 0) || (std::strcmp(call, "ECHO") == 0)
|| (std::strcmp(call, "ALL") == 0))
return true;
return false;
}
Callsign::operator std::string() const
{
return std::string(call);
}
Callsign::operator const char *() const
{
return call;
}
Callsign::operator call_t() const
{
call_t encoded;
uint64_t tmp = 0;
if (strcmp(call, BROADCAST_CALL) == 0) {
encoded.fill(0xFF);
return encoded;
}
if (strcmp(call, INVALID_CALL) == 0) {
encoded.fill(0x00);
return encoded;
}
for (int i = strlen(call) - 1; i >= 0; i--) {
tmp *= 40;
if (call[i] >= 'A' && call[i] <= 'Z') {
tmp += (call[i] - 'A') + 1;
} else if (call[i] >= '0' && call[i] <= '9') {
tmp += (call[i] - '0') + 27;
} else if (call[i] == '-') {
tmp += 37;
} else if (call[i] == '/') {
tmp += 38;
} else if (call[i] == '.') {
tmp += 39;
}
}
// Return encoded callsign in big endian format
auto *ptr = reinterpret_cast<uint8_t *>(&tmp);
std::copy(ptr, ptr + 6, encoded.rbegin());
return encoded;
}
bool Callsign::operator==(const Callsign &other) const
{
// find slash and possibly truncate if slash is within first 3 chars
const char *truncatedLocal = call;
const char *truncatedIncoming = other.call;
const char *slash = std::strchr(call, '/');
if (slash && (slash - call) <= 2)
truncatedLocal = slash + 1;
slash = std::strchr(other.call, '/');
if (slash && (slash - other.call) <= 2)
truncatedIncoming = slash + 1;
return std::strcmp(truncatedLocal, truncatedIncoming) == 0;
}

View File

@ -249,7 +249,23 @@ bool M17Demodulator::update(const bool invertPhase)
if(invertPhase) elem = 0.0f - elem; if(invertPhase) elem = 0.0f - elem;
sample = static_cast< int16_t >(M17::rrc_24k(elem)); sample = static_cast< int16_t >(M17::rrc_24k(elem));
// Update correlator and sample filter for correlation thresholds // Clock recovery reset MUST come before sampling
if((sampleIndex == 0) && resetClockRec) {
clockRec.reset();
resetClockRec = false;
updateSampPoint = false;
}
// Update sample point only when "far enough" from the last sampling,
// to avoid sampling issues when SP rolls over.
int diff = samplingPoint - sampleIndex;
if(updateSampPoint && (std::abs(diff) == SAMPLES_PER_SYMBOL/2)) {
clockRec.update();
samplingPoint = clockRec.samplingPoint();
updateSampPoint = false;
}
clockRec.sample(sample);
correlator.sample(sample); correlator.sample(sample);
corrThreshold = sampleFilter(std::abs(sample)); corrThreshold = sampleFilter(std::abs(sample));
@ -277,7 +293,7 @@ bool M17Demodulator::update(const bool invertPhase)
break; break;
case DemodState::SYNC_UPDATE: case DemodState::SYNC_UPDATE:
syncUpdateState(sample); syncUpdateState();
break; break;
} }
@ -290,6 +306,7 @@ bool M17Demodulator::update(const bool invertPhase)
void M17Demodulator::quantize(stream_sample_t sample) void M17Demodulator::quantize(stream_sample_t sample)
{ {
auto outerDeviation = devEstimator.outerDeviation();
int8_t symbol; int8_t symbol;
if(sample > (2 * outerDeviation.first)/3) if(sample > (2 * outerDeviation.first)/3)
@ -311,13 +328,6 @@ void M17Demodulator::quantize(stream_sample_t sample)
setSymbol(*demodFrame, frameIndex, symbol); setSymbol(*demodFrame, frameIndex, symbol);
frameIndex += 1; frameIndex += 1;
if(frameIndex >= M17_FRAME_SYMBOLS)
{
std::swap(readyFrame, demodFrame);
frameIndex = 0;
newFrame = true;
}
} }
void M17Demodulator::reset() void M17Demodulator::reset()
@ -345,8 +355,9 @@ void M17Demodulator::syncedState()
{ {
// Set sampling point and deviation, zero frame symbol count // Set sampling point and deviation, zero frame symbol count
samplingPoint = streamSync.samplingIndex(); samplingPoint = streamSync.samplingIndex();
outerDeviation = correlator.maxDeviation(samplingPoint); auto deviation = correlator.maxDeviation(samplingPoint);
frameIndex = 0; frameIndex = 0;
devEstimator.init(deviation);
// Quantize the syncword taking data from the correlator // Quantize the syncword taking data from the correlator
// memory. // memory.
@ -373,56 +384,38 @@ void M17Demodulator::lockedState(int16_t sample)
if(sampleIndex != samplingPoint) if(sampleIndex != samplingPoint)
return; return;
// Quantize and update frame at each sampling point
quantize(sample); quantize(sample);
devEstimator.sample(sample);
// When we have reached almost the end of a frame, switch if(frameIndex == M17_FRAME_SYMBOLS) {
// to syncpoint update. devEstimator.update();
if(frameIndex == (M17_FRAME_SYMBOLS - M17_SYNCWORD_SYMBOLS/2)) { std::swap(readyFrame, demodFrame);
frameIndex = 0;
newFrame = true;
updateSampPoint = true;
demodState = DemodState::SYNC_UPDATE; demodState = DemodState::SYNC_UPDATE;
syncCount = SYNCWORD_SAMPLES * 2;
} }
} }
void M17Demodulator::syncUpdateState(int16_t sample) void M17Demodulator::syncUpdateState()
{ {
// Keep filling the ongoing frame! uint8_t streamHd = hammingDistance((*demodFrame)[0], STREAM_SYNC_WORD[0])
if(sampleIndex == samplingPoint)
quantize(sample);
// Find the new correlation peak
int32_t syncThresh = static_cast< int32_t >(corrThreshold * 33.0f);
int8_t syncStatus = streamSync.update(correlator, syncThresh, -syncThresh);
// Correlation has to coincide with a syncword!
if((syncStatus != 0) && (frameIndex == M17_SYNCWORD_SYMBOLS)) {
uint8_t hd = hammingDistance((*demodFrame)[0], STREAM_SYNC_WORD[0])
+ hammingDistance((*demodFrame)[1], STREAM_SYNC_WORD[1]); + hammingDistance((*demodFrame)[1], STREAM_SYNC_WORD[1]);
// Valid sync found: update deviation and sample uint8_t eotHd = hammingDistance((*demodFrame)[0], EOT_SYNC_WORD[0])
// point, then go back to locked state + hammingDistance((*demodFrame)[1], EOT_SYNC_WORD[1]);
if(hd <= 1) {
outerDeviation = correlator.maxDeviation(samplingPoint);
samplingPoint = streamSync.samplingIndex();
missedSyncs = 0;
demodState = DemodState::LOCKED;
return;
}
}
// No syncword found within the window, increase the count if(streamHd <= 1)
// of missed syncs and choose where to go. The lock is lost missedSyncs = 0;
// after four consecutive sync misses. else
if(syncCount == 0) { missedSyncs += 1;
if(missedSyncs >= 4)
// The lock is lost after four consecutive sync misses or an EOT frame.
if((missedSyncs > 4) || (eotHd <= 1))
demodState = DemodState::UNLOCKED; demodState = DemodState::UNLOCKED;
else else
demodState = DemodState::LOCKED; demodState = DemodState::LOCKED;
missedSyncs += 1;
}
syncCount -= 1;
} }
constexpr std::array < float, 3 > M17Demodulator::sfNum; constexpr std::array < float, 3 > M17Demodulator::sfNum;

View File

@ -29,9 +29,13 @@
using namespace M17; using namespace M17;
M17FrameDecoder::M17FrameDecoder() { } M17FrameDecoder::M17FrameDecoder()
{
}
M17FrameDecoder::~M17FrameDecoder() { } M17FrameDecoder::~M17FrameDecoder()
{
}
void M17FrameDecoder::reset() void M17FrameDecoder::reset()
{ {
@ -41,10 +45,10 @@ void M17FrameDecoder::reset()
streamFrame.clear(); streamFrame.clear();
} }
M17FrameType M17FrameDecoder::decodeFrame(const frame_t& frame) M17FrameType M17FrameDecoder::decodeFrame(const frame_t &frame)
{ {
std::array< uint8_t, 2 > syncWord; std::array<uint8_t, 2> syncWord;
std::array< uint8_t, 46 > data; std::array<uint8_t, 46> data;
std::copy_n(frame.begin(), 2, syncWord.begin()); std::copy_n(frame.begin(), 2, syncWord.begin());
std::copy(frame.begin() + 2, frame.end(), data.begin()); std::copy(frame.begin() + 2, frame.end(), data.begin());
@ -55,8 +59,7 @@ M17FrameType M17FrameDecoder::decodeFrame(const frame_t& frame)
auto type = getFrameType(syncWord); auto type = getFrameType(syncWord);
switch(type) switch (type) {
{
case M17FrameType::LINK_SETUP: case M17FrameType::LINK_SETUP:
decodeLSF(data); decodeLSF(data);
break; break;
@ -72,7 +75,8 @@ M17FrameType M17FrameDecoder::decodeFrame(const frame_t& frame)
return type; return type;
} }
M17FrameType M17FrameDecoder::getFrameType(const std::array< uint8_t, 2 >& syncWord) M17FrameType
M17FrameDecoder::getFrameType(const std::array<uint8_t, 2> &syncWord)
{ {
// Preamble // Preamble
M17FrameType type = M17FrameType::PREAMBLE; M17FrameType type = M17FrameType::PREAMBLE;
@ -82,8 +86,8 @@ M17FrameType M17FrameDecoder::getFrameType(const std::array< uint8_t, 2 >& syncW
// Link setup frame // Link setup frame
uint8_t hammDistance = hammingDistance(syncWord[0], LSF_SYNC_WORD[0]) uint8_t hammDistance = hammingDistance(syncWord[0], LSF_SYNC_WORD[0])
+ hammingDistance(syncWord[1], LSF_SYNC_WORD[1]); + hammingDistance(syncWord[1], LSF_SYNC_WORD[1]);
if(hammDistance < minDistance)
{ if (hammDistance < minDistance) {
type = M17FrameType::LINK_SETUP; type = M17FrameType::LINK_SETUP;
minDistance = hammDistance; minDistance = hammDistance;
} }
@ -91,45 +95,43 @@ M17FrameType M17FrameDecoder::getFrameType(const std::array< uint8_t, 2 >& syncW
// Stream frame // Stream frame
hammDistance = hammingDistance(syncWord[0], STREAM_SYNC_WORD[0]) hammDistance = hammingDistance(syncWord[0], STREAM_SYNC_WORD[0])
+ hammingDistance(syncWord[1], STREAM_SYNC_WORD[1]); + hammingDistance(syncWord[1], STREAM_SYNC_WORD[1]);
if(hammDistance < minDistance)
{ if (hammDistance < minDistance) {
type = M17FrameType::STREAM; type = M17FrameType::STREAM;
minDistance = hammDistance; minDistance = hammDistance;
} }
// Check value of minimum hamming distance found, if exceeds the allowed // Check value of minimum hamming distance found, if exceeds the allowed
// limit consider the frame as of unknown type. // limit consider the frame as of unknown type.
if(minDistance > MAX_SYNC_HAMM_DISTANCE) if (minDistance > MAX_SYNC_HAMM_DISTANCE) {
{
type = M17FrameType::UNKNOWN; type = M17FrameType::UNKNOWN;
} }
return type; return type;
} }
void M17FrameDecoder::decodeLSF(const std::array< uint8_t, 46 >& data) void M17FrameDecoder::decodeLSF(const std::array<uint8_t, 46> &data)
{ {
std::array< uint8_t, sizeof(M17LinkSetupFrame) > tmp; std::array<uint8_t, sizeof(M17LinkSetupFrame)> tmp;
viterbi.decodePunctured(data, tmp, LSF_PUNCTURE); viterbi.decodePunctured(data, tmp, LSF_PUNCTURE);
memcpy(&lsf.data, tmp.data(), tmp.size()); memcpy(&lsf.data, tmp.data(), tmp.size());
} }
void M17FrameDecoder::decodeStream(const std::array< uint8_t, 46 >& data) void M17FrameDecoder::decodeStream(const std::array<uint8_t, 46> &data)
{ {
// Extract and unpack the LICH segment contained at beginning of frame // Extract and unpack the LICH segment contained at beginning of frame
lich_t lich; lich_t lich;
std::array < uint8_t, 6 > lsfSegment; std::array<uint8_t, 6> lsfSegment;
std::copy_n(data.begin(), lich.size(), lich.begin()); std::copy_n(data.begin(), lich.size(), lich.begin());
bool decodeOk = decodeLich(lsfSegment, lich); bool decodeOk = decodeLich(lsfSegment, lich);
if(decodeOk) if (decodeOk) {
{
// Append LICH segment // Append LICH segment
uint8_t segmentNum = lsfSegment[5]; uint8_t segmentNum = lsfSegment[5];
uint8_t segmentSize = lsfSegment.size() - 1; uint8_t segmentSize = lsfSegment.size() - 1;
uint8_t *ptr = reinterpret_cast < uint8_t * >(&lsfFromLich.data); uint8_t *ptr = reinterpret_cast<uint8_t *>(&lsfFromLich.data);
ptr += segmentNum * segmentSize; ptr += segmentNum * segmentSize;
memcpy(ptr, lsfSegment.data(), segmentSize); memcpy(ptr, lsfSegment.data(), segmentSize);
@ -137,28 +139,30 @@ void M17FrameDecoder::decodeStream(const std::array< uint8_t, 46 >& data)
lsfSegmentMap |= 1 << segmentNum; lsfSegmentMap |= 1 << segmentNum;
// Check if we have received all the six LICH segments // Check if we have received all the six LICH segments
if(lsfSegmentMap == 0x3F) if (lsfSegmentMap == 0x3F) {
{ if (lsfFromLich.valid())
if(lsfFromLich.valid()) lsf = lsfFromLich; lsf = lsfFromLich;
lsfSegmentMap = 0; lsfSegmentMap = 0;
lsfFromLich.clear(); lsfFromLich.clear();
} }
} }
// Extract and decode stream data // Extract and decode stream data
std::array< uint8_t, 34 > punctured; std::array<uint8_t, 34> punctured;
std::array< uint8_t, sizeof(M17StreamFrame) > tmp; std::array<uint8_t, sizeof(M17StreamFrame)> tmp;
auto begin = data.begin(); auto begin = data.begin();
begin += lich.size(); begin += lich.size();
std::copy(begin, data.end(), punctured.begin()); std::copy(begin, data.end(), punctured.begin());
viterbi.decodePunctured(punctured, tmp, DATA_PUNCTURE); // Skip payload copy if BER is too high to avoid audio artifacts
uint16_t bitErrs = viterbi.decodePunctured(punctured, tmp, DATA_PUNCTURE);
if (bitErrs < MAX_VITERBI_ERRORS)
memcpy(&streamFrame.data, tmp.data(), tmp.size()); memcpy(&streamFrame.data, tmp.data(), tmp.size());
} }
bool M17FrameDecoder::decodeLich(std::array < uint8_t, 6 >& segment, bool M17FrameDecoder::decodeLich(std::array<uint8_t, 6> &segment,
const lich_t& lich) const lich_t &lich)
{ {
/* /*
* Extract and unpack the LICH segment contained in the frame header. * Extract and unpack the LICH segment contained in the frame header.
@ -176,26 +180,21 @@ bool M17FrameDecoder::decodeLich(std::array < uint8_t, 6 >& segment,
size_t index = 0; size_t index = 0;
uint32_t block = 0; uint32_t block = 0;
for(size_t i = 0; i < 4; i++) for (size_t i = 0; i < 4; i++) {
{ memcpy(&block, lich.data() + 3 * i, 3);
memcpy(&block, lich.data() + 3*i, 3);
block = __builtin_bswap32(block) >> 8; block = __builtin_bswap32(block) >> 8;
uint16_t decoded = golay24_decode(block); uint16_t decoded = golay24_decode(block);
// Unrecoverable error, abort decoding // Unrecoverable error, abort decoding
if(decoded == 0xFFFF) if (decoded == 0xFFFF) {
{
segment.fill(0x00); segment.fill(0x00);
return false; return false;
} }
if(i & 1) if (i & 1) {
{
segment[index++] |= (decoded >> 8); // upper 4 bits segment[index++] |= (decoded >> 8); // upper 4 bits
segment[index++] = (decoded & 0xFF); // lower 8 bits segment[index++] = (decoded & 0xFF); // lower 8 bits
} } else {
else
{
segment[index++] |= (decoded >> 4); // upper 8 bits segment[index++] |= (decoded >> 4); // upper 8 bits
segment[index] = (decoded & 0x0F) << 4; // lower 4 bits segment[index] = (decoded & 0x0F) << 4; // lower 4 bits
} }
@ -206,7 +205,7 @@ bool M17FrameDecoder::decodeLich(std::array < uint8_t, 6 >& segment,
// zero and five. // zero and five.
segment[5] >>= 5; segment[5] >>= 5;
if(segment[5] > 5) if (segment[5] > 5)
return false; return false;
return true; return true;

View File

@ -41,24 +41,24 @@ void M17LinkSetupFrame::clear()
data.dst.fill(0xFF); data.dst.fill(0xFF);
} }
void M17LinkSetupFrame::setSource(const std::string& callsign) void M17LinkSetupFrame::setSource(const Callsign& callsign)
{ {
encode_callsign(callsign, data.src); data.src = callsign;
} }
std::string M17LinkSetupFrame::getSource() Callsign M17LinkSetupFrame::getSource()
{ {
return decode_callsign(data.src); return Callsign(data.src);
} }
void M17LinkSetupFrame::setDestination(const std::string& callsign) void M17LinkSetupFrame::setDestination(const Callsign& callsign)
{ {
encode_callsign(callsign, data.dst); data.dst = callsign;
} }
std::string M17LinkSetupFrame::getDestination() Callsign M17LinkSetupFrame::getDestination()
{ {
return decode_callsign(data.dst); return Callsign(data.dst);
} }
streamType_t M17LinkSetupFrame::getType() streamType_t M17LinkSetupFrame::getType()

View File

@ -206,8 +206,9 @@ void OpMode_M17::rxState(rtxStatus_t *const status)
dataValid = true; dataValid = true;
// Retrieve stream source and destination data // Retrieve stream source and destination data
std::string dst = lsf.getDestination(); Callsign dst = lsf.getDestination();
std::string src = lsf.getSource(); Callsign src = lsf.getSource();
strncpy(status->M17_dst, dst, 10);
// Retrieve extended callsign data // Retrieve extended callsign data
streamType_t streamType = lsf.getType(); streamType_t streamType = lsf.getType();
@ -218,8 +219,8 @@ void OpMode_M17::rxState(rtxStatus_t *const status)
extendedCall = true; extendedCall = true;
meta_t& meta = lsf.metadata(); meta_t& meta = lsf.metadata();
std::string exCall1 = decode_callsign(meta.extended_call_sign.call1); Callsign exCall1(meta.extended_call_sign.call1);
std::string exCall2 = decode_callsign(meta.extended_call_sign.call2); Callsign exCall2(meta.extended_call_sign.call2);
// //
// The source callsign only contains the last link when // The source callsign only contains the last link when
@ -227,21 +228,16 @@ void OpMode_M17::rxState(rtxStatus_t *const status)
// the true source of a transmission, we need to store the first // the true source of a transmission, we need to store the first
// extended callsign in M17_src. // extended callsign in M17_src.
// //
strncpy(status->M17_src, exCall1.c_str(), 10); strncpy(status->M17_src, exCall1, 10);
strncpy(status->M17_refl, exCall2.c_str(), 10); strncpy(status->M17_refl, exCall2, 10);
strncpy(status->M17_link, src, 10);
extendedCall = true; } else {
strncpy(status->M17_src, src, 10);
} }
// Set source and destination fields. // Set source and destination fields.
// If we have received an extended callsign the src will be the RF link address // If we have received an extended callsign the src will be the RF link address
// The M17_src will already be stored from the extended callsign // The M17_src will already be stored from the extended callsign
strncpy(status->M17_dst, dst.c_str(), 10);
if(extendedCall)
strncpy(status->M17_link, src.c_str(), 10);
else
strncpy(status->M17_src, src.c_str(), 10);
// Check CAN on RX, if enabled. // Check CAN on RX, if enabled.
// If check is disabled, force match to true. // If check is disabled, force match to true.
@ -250,7 +246,8 @@ void OpMode_M17::rxState(rtxStatus_t *const status)
// Check if the destination callsign of the incoming transmission // Check if the destination callsign of the incoming transmission
// matches with ours // matches with ours
bool callMatch = compareCallsigns(std::string(status->source_address), dst); bool callMatch = (Callsign(status->source_address) == dst)
|| dst.isSpecial();
// Open audio path only if CAN and callsign match // Open audio path only if CAN and callsign match
uint8_t pthSts = audioPath_getStatus(rxAudioPath); uint8_t pthSts = audioPath_getStatus(rxAudioPath);
@ -306,13 +303,14 @@ void OpMode_M17::txState(rtxStatus_t *const status)
{ {
startTx = false; startTx = false;
std::string src(status->source_address);
std::string dst(status->destination_address);
M17LinkSetupFrame lsf; M17LinkSetupFrame lsf;
lsf.clear(); lsf.clear();
lsf.setSource(src); lsf.setSource(status->source_address);
if(!dst.empty()) lsf.setDestination(dst);
Callsign dst(status->destination_address);
if(!dst.isEmpty())
lsf.setDestination(dst);
streamType_t type; streamType_t type;
type.fields.dataMode = M17_DATAMODE_STREAM; // Stream type.fields.dataMode = M17_DATAMODE_STREAM; // Stream

View File

@ -69,8 +69,12 @@ openrtx/include/interfaces/radio.h
openrtx/include/peripherals/gps.h openrtx/include/peripherals/gps.h
openrtx/include/peripherals/rng.h openrtx/include/peripherals/rng.h
openrtx/include/peripherals/rtc.h openrtx/include/peripherals/rtc.h
openrtx/include/protocols/M17/Callsign.hpp
openrtx/include/protocols/M17/M17FrameDecoder.hpp
openrtx/src/core/dsp.cpp openrtx/src/core/dsp.cpp
openrtx/src/core/memory_profiling.cpp openrtx/src/core/memory_profiling.cpp
openrtx/src/protocols/M17/Callsign.cpp
openrtx/src/protocols/M17/M17FrameDecoder.cpp
platform/drivers/ADC/ADC0_GDx.h platform/drivers/ADC/ADC0_GDx.h
platform/drivers/audio/MAX9814.h platform/drivers/audio/MAX9814.h
platform/drivers/baseband/MCP4551.h platform/drivers/baseband/MCP4551.h
@ -88,6 +92,7 @@ platform/targets/linux/emulator/sdl_engine.h
platform/targets/ttwrplus/pmu.h platform/targets/ttwrplus/pmu.h
tests/platform/mic_test.c tests/platform/mic_test.c
tests/platform/codec2_encode_test.c tests/platform/codec2_encode_test.c
tests/unit/M17_callsign.cpp
EOF EOF
) )

View File

@ -0,0 +1,90 @@
/***************************************************************************
* Copyright (C) 2021 - 2025 by Federico Amedeo Izzo IU2NUO, *
* Niccolò Izzo IU2KIN *
* Frederik Saraci IU2NRO *
* Silvano Seva IU2KWO *
* *
* *
* 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 3 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, see <http://www.gnu.org/licenses/> *
***************************************************************************/
#include <cstdio>
#include <cstdint>
#include <cstring>
#include <array>
#include <algorithm>
#include <iostream>
#include "protocols/M17/Callsign.hpp"
#include "protocols/M17/M17Datatypes.hpp"
using namespace std;
int test_encode_ab1cd()
{
const char callsign[] = "AB1CD";
M17::call_t expected = { 0x00, 0x00, 0x00, 0x9f, 0xdd, 0x51 };
M17::Callsign test = M17::Callsign(callsign);
M17::call_t actual = test;
if (equal(begin(actual), end(actual), begin(expected), end(expected))) {
return 0;
} else {
return -1;
}
}
int test_encode_empty()
{
const char callsign[] = "";
M17::call_t expected = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
M17::Callsign test = M17::Callsign(callsign);
M17::call_t actual = test;
if (equal(begin(actual), end(actual), begin(expected), end(expected))) {
return 0;
} else {
return -1;
}
}
int test_decode_ab1cd()
{
M17::call_t callsign = { 0x00, 0x00, 0x00, 0x9f, 0xdd, 0x51 };
M17::Callsign test = M17::Callsign(callsign);
const char expected[] = "AB1CD";
const char *actual = test;
if (strcmp(expected, actual) == 0) {
return 0;
} else {
return -1;
}
}
int main()
{
if (test_encode_ab1cd()) {
printf("Error in encoding callsign ab1cd!\n");
return -1;
}
if (test_encode_empty()) {
printf("Error in encoding empty callsign !\n");
return -1;
}
if (test_decode_ab1cd()) {
printf("Error in decoding callsign ab1cd!\n");
return -1;
}
return 0;
}