2 Commits

Author SHA1 Message Date
e7d7c0e1c1 dma fix priority and debug 2026-04-02 17:25:10 +03:00
af3e012aac fix msgTypeReceive and isReceive 2026-03-30 13:34:04 +03:00
51 changed files with 89288 additions and 2593 deletions

5
.gitignore vendored
View File

@ -5,8 +5,3 @@ log/*
/.vscode
*.zip
**/__pycache__
Analyzer/raw/dll/*.dll
Analyzer/raw/dll/*.so
Analyzer/raw/dll/*.dylib
/Analyzer/raw/IR_Fox/.github
**/.build

View File

@ -1,2 +0,0 @@
/build
.DS_Store

View File

@ -1,26 +0,0 @@
cmake_minimum_required(VERSION 3.13)
project(IrFoxAnalyzer)
add_definitions(-DLOGIC2)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake)
include(ExternalAnalyzerSDK)
set(SOURCES
src/IrFoxAnalyzer.cpp
src/IrFoxAnalyzer.h
src/IrFoxDecoder.cpp
src/IrFoxDecoder.h
src/IrFoxAnalyzerResults.cpp
src/IrFoxAnalyzerResults.h
src/IrFoxAnalyzerSettings.cpp
src/IrFoxAnalyzerSettings.h
src/IrFoxSimulationDataGenerator.cpp
src/IrFoxSimulationDataGenerator.h
)
add_analyzer_plugin(${PROJECT_NAME} SOURCES ${SOURCES})

View File

@ -1,49 +0,0 @@
{
"version": 3,
"cmakeMinimumRequired": {
"major": 3,
"minor": 19,
"patch": 0
},
"configurePresets": [
{
"name": "win-vs2022-x64",
"displayName": "Visual Studio 2022 (x64)",
"generator": "Visual Studio 17 2022",
"architecture": "x64",
"binaryDir": "${sourceDir}/build"
},
{
"name": "win-vs2019-x64",
"displayName": "Visual Studio 2019 (x64)",
"generator": "Visual Studio 16 2019",
"architecture": "x64",
"binaryDir": "${sourceDir}/build"
},
{
"name": "win-nmake-release",
"displayName": "NMake Release (только из «x64 Native Tools Command Prompt for VS»)",
"generator": "NMake Makefiles",
"binaryDir": "${sourceDir}/build-nmake",
"cacheVariables": {
"CMAKE_BUILD_TYPE": "Release"
}
}
],
"buildPresets": [
{
"name": "win-release",
"configurePreset": "win-vs2022-x64",
"configuration": "Release"
},
{
"name": "win-release-vs2019",
"configurePreset": "win-vs2019-x64",
"configuration": "Release"
},
{
"name": "nmake-release",
"configurePreset": "win-nmake-release"
}
]
}

View File

@ -1,21 +0,0 @@
@echo off
setlocal EnableDelayedExpansion
cd /d "%~dp0"
if not exist build\CMakeCache.txt (
echo Run configure_msvc.bat first.
exit /b 1
)
set "VSWHERE=%ProgramFiles(x86)%\Microsoft Visual Studio\Installer\vswhere.exe"
for /f "usebackq tokens=*" %%i in (`"%VSWHERE%" -latest -products * -requires Microsoft.VisualStudio.Component.VC.Tools.x86.x64 -property installationPath`) do set "VSINSTALL=%%i"
if not defined VSINSTALL (
echo MSVC not found. Add C++ workload in Visual Studio Installer.
exit /b 1
)
call "!VSINSTALL!\Common7\Tools\VsDevCmd.bat" -arch=x64 -host_arch=x64
if errorlevel 1 exit /b 1
cmake --build build
pause
exit /b %ERRORLEVEL%

View File

@ -1,66 +0,0 @@
include(FetchContent)
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED YES)
if(NOT CMAKE_RUNTIME_OUTPUT_DIRECTORY OR NOT CMAKE_LIBRARY_OUTPUT_DIRECTORY)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin/)
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin/)
endif()
if(NOT TARGET Saleae::AnalyzerSDK)
FetchContent_Declare(
analyzersdk
GIT_REPOSITORY https://github.com/saleae/AnalyzerSDK.git
GIT_TAG master
GIT_SHALLOW True
GIT_PROGRESS True
)
FetchContent_GetProperties(analyzersdk)
if(NOT analyzersdk_POPULATED)
FetchContent_Populate(analyzersdk)
include(${analyzersdk_SOURCE_DIR}/AnalyzerSDKConfig.cmake)
if(APPLE OR WIN32)
get_target_property(analyzersdk_lib_location Saleae::AnalyzerSDK IMPORTED_LOCATION)
if(CMAKE_LIBRARY_OUTPUT_DIRECTORY)
file(COPY ${analyzersdk_lib_location} DESTINATION ${CMAKE_LIBRARY_OUTPUT_DIRECTORY})
else()
message(WARNING "Please define CMAKE_RUNTIME_OUTPUT_DIRECTORY and CMAKE_LIBRARY_OUTPUT_DIRECTORY if you want unit tests to locate ${analyzersdk_lib_location}")
endif()
endif()
endif()
endif()
# Shared folder for all Saleae LLA plugins in this repo: Analyzer/raw/dll
set(ANALYZER_DLL_OUT_DIR "${CMAKE_SOURCE_DIR}/../dll")
get_filename_component(ANALYZER_DLL_OUT_DIR "${ANALYZER_DLL_OUT_DIR}" ABSOLUTE)
file(MAKE_DIRECTORY "${ANALYZER_DLL_OUT_DIR}")
function(add_analyzer_plugin TARGET)
set(options)
set(single_value_args)
set(multi_value_args SOURCES)
cmake_parse_arguments(_p "${options}" "${single_value_args}" "${multi_value_args}" ${ARGN})
add_library(${TARGET} MODULE ${_p_SOURCES})
target_link_libraries(${TARGET} PRIVATE Saleae::AnalyzerSDK)
set(ANALYZER_DESTINATION "Analyzers")
install(TARGETS ${TARGET} RUNTIME DESTINATION ${ANALYZER_DESTINATION}
LIBRARY DESTINATION ${ANALYZER_DESTINATION})
set_target_properties(${TARGET} PROPERTIES
RUNTIME_OUTPUT_DIRECTORY "${ANALYZER_DLL_OUT_DIR}"
LIBRARY_OUTPUT_DIRECTORY "${ANALYZER_DLL_OUT_DIR}")
if(CMAKE_CONFIGURATION_TYPES)
foreach(CFG ${CMAKE_CONFIGURATION_TYPES})
string(TOUPPER ${CFG} CFG_UPPER)
set_target_properties(${TARGET} PROPERTIES
RUNTIME_OUTPUT_DIRECTORY_${CFG_UPPER} "${ANALYZER_DLL_OUT_DIR}"
LIBRARY_OUTPUT_DIRECTORY_${CFG_UPPER} "${ANALYZER_DLL_OUT_DIR}")
endforeach()
endif()
endfunction()

View File

@ -1,39 +0,0 @@
@echo off
setlocal EnableDelayedExpansion
cd /d "%~dp0"
echo === IrFoxAnalyzer: configure with MSVC ===
echo.
set "VSWHERE=%ProgramFiles(x86)%\Microsoft Visual Studio\Installer\vswhere.exe"
if not exist "%VSWHERE%" (
echo [ERROR] vswhere not found. Install one of:
echo - Visual Studio 2022 with workload "Desktop development with C++"
echo - Build Tools for Visual Studio 2022: https://visualstudio.microsoft.com/visual-cpp-build-tools/
echo ^(select "Desktop development with C++" / MSVC, Windows SDK^)
exit /b 1
)
for /f "usebackq tokens=*" %%i in (`"%VSWHERE%" -latest -products * -requires Microsoft.VisualStudio.Component.VC.Tools.x86.x64 -property installationPath`) do set "VSINSTALL=%%i"
if not defined VSINSTALL (
echo [ERROR] MSVC toolset not found. Add "Desktop development with C++" in Visual Studio Installer.
exit /b 1
)
echo Found: !VSINSTALL!
call "!VSINSTALL!\Common7\Tools\VsDevCmd.bat" -arch=x64 -host_arch=x64
if errorlevel 1 exit /b 1
if exist build rmdir /s /q build
if exist build-nmake rmdir /s /q build-nmake
mkdir build
cd build
cmake .. -G "NMake Makefiles" -DCMAKE_BUILD_TYPE=Release
if errorlevel 1 exit /b 1
echo.
echo Configure OK. Build: build_msvc.bat ^(or from same VS env: cd build ^& cmake --build .^)
echo Output DLL: ..\dll\ ^(all analyzers share this folder^)
pause
exit /b 0

View File

@ -1,280 +0,0 @@
#include "IrFoxAnalyzer.h"
#include "IrFoxAnalyzerSettings.h"
#include "IrFoxDecoder.h"
#include <AnalyzerChannelData.h>
#include <AnalyzerResults.h>
#include <algorithm>
#include <cstdio>
#include <cstring>
#include <string>
#include <vector>
IrFoxAnalyzer::IrFoxAnalyzer()
: Analyzer2(),
mSettings(),
mSimulationInitilized(false)
{
SetAnalyzerSettings(&mSettings);
UseFrameV2();
}
IrFoxAnalyzer::~IrFoxAnalyzer()
{
KillThread();
}
void IrFoxAnalyzer::SetupResults()
{
m_packet_hex_by_frame.clear();
mResults.reset(new IrFoxAnalyzerResults(this, &mSettings));
SetAnalyzerResults(mResults.get());
mResults->AddChannelBubblesWillAppearOn(mSettings.mInputChannel);
}
static void append_hex(std::string& s, const uint8_t* p, size_t n, size_t max_bytes = 64)
{
static const char* hd = "0123456789abcdef";
const size_t m = n < max_bytes ? n : max_bytes;
for (size_t i = 0; i < m; i++)
{
s.push_back(hd[p[i] >> 4]);
s.push_back(hd[p[i] & 0xFu]);
if (i + 1 < m)
s.push_back(' ');
}
if (n > max_bytes)
s += "...";
}
const char* IrFoxAnalyzer::PacketHexForFrame(U64 frame_id)
{
auto it = m_packet_hex_by_frame.find(frame_id);
if (it == m_packet_hex_by_frame.end())
return "";
m_hex_scratch = it->second;
return m_hex_scratch.c_str();
}
const char* IrFoxAnalyzer::BubbleTextForFrame(U64 frame_id) const
{
auto it = m_bubble_text_by_frame.find(frame_id);
if (it == m_bubble_text_by_frame.end())
return "";
m_bubble_scratch = it->second;
return m_bubble_scratch.c_str();
}
void IrFoxAnalyzer::WorkerThread()
{
mIr = GetAnalyzerChannelData(mSettings.mInputChannel);
m_packet_hex_by_frame.clear();
m_bubble_text_by_frame.clear();
const U32 fs = GetSampleRate();
IrFoxDecoder decoder;
decoder.reset();
/** Потоковый фильтр: убирает импульсы короче kMinFilteredPulseUs (иголки/дребезг в сэмплах). */
const U64 min_seg_samples =
std::max<U64>(1ULL, static_cast<U64>((static_cast<double>(irfox::kMinFilteredPulseUs) * 1e-6) * static_cast<double>(fs) + 0.5));
struct RawEdge
{
U64 sample;
bool rising;
};
std::vector<RawEdge> pending;
U64 last_dec_edge_sample = 0;
bool last_dec_edge_valid = false;
auto collapse_short_pairs = [&]() {
for (size_t i = 0; i + 1 < pending.size();)
{
if (pending[i + 1].sample - pending[i].sample < min_seg_samples)
{
pending.erase(pending.begin() + static_cast<std::ptrdiff_t>(i),
pending.begin() + static_cast<std::ptrdiff_t>(i + 2));
if (i > 0)
--i;
}
else
++i;
}
};
auto strip_vs_last_decoder = [&]() {
for (;;)
{
collapse_short_pairs();
if (!last_dec_edge_valid || pending.empty())
return;
if (pending[0].sample - last_dec_edge_sample >= min_seg_samples)
return;
pending.erase(pending.begin());
}
};
U32 frames_since_commit = 0;
const U32 kCommitBatch = 256;
IrFoxOnBit on_bit = [&](const IrFoxEmitBit& e) {
Frame frame;
frame.mStartingSampleInclusive = static_cast<S64>(e.start_sample);
frame.mEndingSampleInclusive = static_cast<S64>(e.end_sample);
frame.mType = e.frame_type;
frame.mData1 = e.bit_value;
frame.mData2 = e.bit_index | (U64(e.err_low) << 16) | (U64(e.err_high) << 24) | (U64(e.err_other) << 32);
frame.mFlags = e.mflags;
// В SDK только ERROR/WARNING меняют цвет бабла; sync выделяем янтарным (как warning), данные — обычные.
if (e.frame_type == IRF_FT_SYNC_BIT)
frame.mFlags |= DISPLAY_AS_WARNING_FLAG;
const U64 fid = mResults->AddFrame(frame);
if (e.bubble_text[0] != '\0')
m_bubble_text_by_frame[fid] = e.bubble_text;
if (++frames_since_commit >= kCommitBatch)
{
mResults->CommitResults();
frames_since_commit = 0;
}
};
IrFoxOnPacket on_pkt = [&](const IrFoxEmitPacket& p) {
Frame frame;
frame.mStartingSampleInclusive = static_cast<S64>(p.start_sample);
frame.mEndingSampleInclusive = static_cast<S64>(p.end_sample);
frame.mType = p.crc_ok ? IRF_FT_PACKET_OK : IRF_FT_PACKET_CRC_FAIL;
frame.mData1 = p.pack_size;
frame.mData2 = (U64(p.err_low) << 0) | (U64(p.err_high) << 8) | (U64(p.err_other) << 16);
if (!p.crc_ok)
frame.mFlags |= DISPLAY_AS_ERROR_FLAG;
const U64 fid = mResults->AddFrame(frame);
std::string hx;
append_hex(hx, p.data_bytes, p.pack_size);
m_packet_hex_by_frame[fid] = std::move(hx);
FrameV2 fv2;
fv2.AddBoolean("crc_ok", p.crc_ok);
fv2.AddInteger("len", static_cast<S64>(p.pack_size));
fv2.AddInteger("err_low", static_cast<S64>(p.err_low));
fv2.AddInteger("err_high", static_cast<S64>(p.err_high));
fv2.AddInteger("err_other", static_cast<S64>(p.err_other));
fv2.AddByteArray("data", p.data_bytes, p.pack_size);
mResults->AddFrameV2(fv2, p.crc_ok ? "packet_ok" : "packet_bad", static_cast<U64>(p.start_sample),
static_cast<U64>(p.end_sample));
if (++frames_since_commit >= kCommitBatch)
{
mResults->CommitResults();
frames_since_commit = 0;
}
};
auto emit_confirmed_edges = [&]() {
for (;;)
{
collapse_short_pairs();
strip_vs_last_decoder();
if (pending.size() < 2)
return;
if (pending[1].sample - pending[0].sample < min_seg_samples)
continue;
decoder.processEdge(pending[0].sample, pending[0].rising, fs, on_bit, on_pkt);
last_dec_edge_sample = pending[0].sample;
last_dec_edge_valid = true;
pending.erase(pending.begin());
}
};
auto flush_pending_tail = [&]() {
collapse_short_pairs();
strip_vs_last_decoder();
while (pending.size() >= 2 && pending[1].sample - pending[0].sample >= min_seg_samples)
{
decoder.processEdge(pending[0].sample, pending[0].rising, fs, on_bit, on_pkt);
last_dec_edge_sample = pending[0].sample;
last_dec_edge_valid = true;
pending.erase(pending.begin());
collapse_short_pairs();
strip_vs_last_decoder();
}
if (pending.size() == 1)
{
decoder.processEdge(pending[0].sample, pending[0].rising, fs, on_bit, on_pkt);
last_dec_edge_sample = pending[0].sample;
last_dec_edge_valid = true;
pending.clear();
}
};
for (;;)
{
CheckIfThreadShouldExit();
const U64 segment_start = mIr->GetSampleNumber();
const BitState level = mIr->GetBitState();
mIr->AdvanceToNextEdge();
const U64 edge_sample = mIr->GetSampleNumber();
if (edge_sample == segment_start)
break;
const BitState new_level = mIr->GetBitState();
const bool rising = (new_level == BIT_HIGH);
pending.push_back(RawEdge{edge_sample, rising});
emit_confirmed_edges();
ReportProgress(edge_sample);
}
flush_pending_tail();
decoder.flushEnd(mIr->GetSampleNumber(), fs, on_bit, on_pkt);
if (frames_since_commit != 0)
mResults->CommitResults();
}
bool IrFoxAnalyzer::NeedsRerun()
{
return false;
}
U32 IrFoxAnalyzer::GenerateSimulationData(U64 minimum_sample_index, U32 device_sample_rate,
SimulationChannelDescriptor** simulation_channels)
{
if (mSimulationInitilized == false)
{
mSimulationDataGenerator.Initialize(GetSimulationSampleRate(), &mSettings);
mSimulationInitilized = true;
}
return mSimulationDataGenerator.GenerateSimulationData(minimum_sample_index, device_sample_rate,
simulation_channels);
}
U32 IrFoxAnalyzer::GetMinimumSampleRateHz()
{
return 200000;
}
const char* IrFoxAnalyzer::GetAnalyzerName() const
{
return "IR Fox";
}
const char* GetAnalyzerName()
{
return "IR Fox";
}
Analyzer* CreateAnalyzer()
{
return new IrFoxAnalyzer();
}
void DestroyAnalyzer(Analyzer* analyzer)
{
delete analyzer;
}

View File

@ -1,49 +0,0 @@
#ifndef IRFOX_ANALYZER_H
#define IRFOX_ANALYZER_H
#include <Analyzer.h>
#include "IrFoxAnalyzerSettings.h"
#include "IrFoxAnalyzerResults.h"
#include "IrFoxSimulationDataGenerator.h"
#include <memory>
#include <string>
#include <unordered_map>
class ANALYZER_EXPORT IrFoxAnalyzer : public Analyzer2
{
public:
IrFoxAnalyzer();
virtual ~IrFoxAnalyzer();
virtual void SetupResults();
virtual void WorkerThread();
virtual U32 GenerateSimulationData(U64 newest_sample_requested, U32 sample_rate,
SimulationChannelDescriptor** simulation_channels);
virtual U32 GetMinimumSampleRateHz();
virtual const char* GetAnalyzerName() const;
virtual bool NeedsRerun();
const char* PacketHexForFrame(U64 frame_id);
const char* BubbleTextForFrame(U64 frame_id) const;
protected:
IrFoxAnalyzerSettings mSettings;
std::unique_ptr<IrFoxAnalyzerResults> mResults;
AnalyzerChannelData* mIr;
IrFoxSimulationDataGenerator mSimulationDataGenerator;
bool mSimulationInitilized;
std::unordered_map<U64, std::string> m_packet_hex_by_frame;
std::unordered_map<U64, std::string> m_bubble_text_by_frame;
mutable std::string m_hex_scratch;
mutable std::string m_bubble_scratch;
};
extern "C" ANALYZER_EXPORT const char* __cdecl GetAnalyzerName();
extern "C" ANALYZER_EXPORT Analyzer* __cdecl CreateAnalyzer();
extern "C" ANALYZER_EXPORT void __cdecl DestroyAnalyzer(Analyzer* analyzer);
#endif

View File

@ -1,175 +0,0 @@
#include "IrFoxAnalyzerResults.h"
#include <AnalyzerHelpers.h>
#include <AnalyzerResults.h>
#include "IrFoxAnalyzer.h"
#include "IrFoxAnalyzerSettings.h"
#include "IrFoxDecoder.h"
#include <cstdio>
#include <fstream>
IrFoxAnalyzerResults::IrFoxAnalyzerResults(IrFoxAnalyzer* analyzer, IrFoxAnalyzerSettings* settings)
: AnalyzerResults(),
mSettings(settings),
mAnalyzer(analyzer)
{
}
IrFoxAnalyzerResults::~IrFoxAnalyzerResults()
{
}
void IrFoxAnalyzerResults::GenerateBubbleText(U64 frame_index, Channel& channel, DisplayBase display_base)
{
(void)display_base;
(void)channel;
ClearResultStrings();
Frame frame = GetFrame(frame_index);
char line[256];
switch (frame.mType)
{
case IRF_FT_DATA_BIT:
case IRF_FT_SYNC_BIT:
case IRF_FT_PREAMBLE:
case IRF_FT_OVERFLOW:
case IRF_FT_ABORT:
{
const char* bt = mAnalyzer->BubbleTextForFrame(frame_index);
if (bt && bt[0])
AddResultString(bt);
else if (frame.mType == IRF_FT_DATA_BIT)
AddResultString(frame.mData1 ? "1" : "0");
else if (frame.mType == IRF_FT_SYNC_BIT)
{
snprintf(line, sizeof line, "sync: %s", frame.mData1 ? "1" : "0");
AddResultString(line);
}
else if (frame.mType == IRF_FT_OVERFLOW)
AddResultString("OVF");
else if (frame.mType == IRF_FT_ABORT)
AddResultString("SYNC!");
else
AddResultString("PRE");
break;
}
case IRF_FT_PACKET_OK:
case IRF_FT_PACKET_CRC_FAIL:
{
snprintf(line, sizeof line, "%s %lluB", frame.mType == IRF_FT_PACKET_OK ? "OK" : "CRC",
(unsigned long long)frame.mData1);
AddResultString(line);
const char* hx = mAnalyzer->PacketHexForFrame(frame_index);
if (hx && hx[0])
AddResultString(hx);
break;
}
default:
snprintf(line, sizeof line, "? type=%u", static_cast<unsigned>(frame.mType));
AddResultString(line);
break;
}
}
void IrFoxAnalyzerResults::GenerateExportFile(const char* file, DisplayBase display_base, U32 export_type_user_id)
{
(void)export_type_user_id;
(void)display_base;
std::ofstream file_stream(file, std::ios::out);
const U64 trigger_sample = mAnalyzer->GetTriggerSample();
const U32 sample_rate = mAnalyzer->GetSampleRate();
file_stream << "Time[s],Type,Data1,bit_idx,err_low,err_high,err_other,Flags,Hex" << std::endl;
const U64 num_frames = GetNumFrames();
for (U32 i = 0; i < num_frames; i++)
{
Frame frame = GetFrame(i);
char time_str[128];
AnalyzerHelpers::GetTimeString(frame.mStartingSampleInclusive, trigger_sample, sample_rate, time_str, 128);
const char* typ = "?";
switch (frame.mType)
{
case IRF_FT_DATA_BIT:
typ = "D";
break;
case IRF_FT_SYNC_BIT:
typ = "S";
break;
case IRF_FT_PACKET_OK:
typ = "OK";
break;
case IRF_FT_PACKET_CRC_FAIL:
typ = "CRC";
break;
case IRF_FT_OVERFLOW:
typ = "OVF";
break;
case IRF_FT_ABORT:
typ = "ABORT";
break;
case IRF_FT_PREAMBLE:
typ = "PRE";
break;
default:
break;
}
const char* hx = mAnalyzer->PacketHexForFrame(i);
if (!hx)
hx = "";
U64 bit_idx = 0;
U32 err_l = 0, err_h = 0, err_o = 0;
if (frame.mType == IRF_FT_DATA_BIT || frame.mType == IRF_FT_SYNC_BIT ||
frame.mType == IRF_FT_OVERFLOW || frame.mType == IRF_FT_ABORT)
{
bit_idx = frame.mData2 & 0xFFFFull;
err_l = static_cast<U32>((frame.mData2 >> 16) & 0xFFull);
err_h = static_cast<U32>((frame.mData2 >> 24) & 0xFFull);
err_o = static_cast<U32>((frame.mData2 >> 32) & 0xFFull);
}
file_stream << time_str << "," << typ << "," << frame.mData1 << "," << bit_idx << "," << err_l << "," << err_h
<< "," << err_o << "," << static_cast<unsigned>(frame.mFlags) << "," << hx << std::endl;
if (UpdateExportProgressAndCheckForCancel(i, num_frames) == true)
{
file_stream.close();
return;
}
}
file_stream.close();
}
void IrFoxAnalyzerResults::GenerateFrameTabularText(U64 frame_index, DisplayBase display_base)
{
#ifdef SUPPORTS_PROTOCOL_SEARCH
(void)display_base;
Frame frame = GetFrame(frame_index);
ClearTabularText();
char buf[64];
snprintf(buf, sizeof buf, "t%u", static_cast<unsigned>(frame.mType));
AddTabularText(buf);
snprintf(buf, sizeof buf, "%llu", (unsigned long long)frame.mData1);
AddTabularText(buf);
#endif
}
void IrFoxAnalyzerResults::GeneratePacketTabularText(U64 packet_id, DisplayBase display_base)
{
(void)packet_id;
(void)display_base;
}
void IrFoxAnalyzerResults::GenerateTransactionTabularText(U64 transaction_id, DisplayBase display_base)
{
(void)transaction_id;
(void)display_base;
}

View File

@ -1,27 +0,0 @@
#ifndef IRFOX_ANALYZER_RESULTS
#define IRFOX_ANALYZER_RESULTS
#include <AnalyzerResults.h>
class IrFoxAnalyzer;
class IrFoxAnalyzerSettings;
class IrFoxAnalyzerResults : public AnalyzerResults
{
public:
IrFoxAnalyzerResults(IrFoxAnalyzer* analyzer, IrFoxAnalyzerSettings* settings);
virtual ~IrFoxAnalyzerResults();
virtual void GenerateBubbleText(U64 frame_index, Channel& channel, DisplayBase display_base);
virtual void GenerateExportFile(const char* file, DisplayBase display_base, U32 export_type_user_id);
virtual void GenerateFrameTabularText(U64 frame_index, DisplayBase display_base);
virtual void GeneratePacketTabularText(U64 packet_id, DisplayBase display_base);
virtual void GenerateTransactionTabularText(U64 transaction_id, DisplayBase display_base);
protected:
IrFoxAnalyzerSettings* mSettings;
IrFoxAnalyzer* mAnalyzer;
};
#endif

View File

@ -1,62 +0,0 @@
#include "IrFoxAnalyzerSettings.h"
#include <AnalyzerHelpers.h>
IrFoxAnalyzerSettings::IrFoxAnalyzerSettings()
: mInputChannel(UNDEFINED_CHANNEL),
mInputChannelInterface()
{
mInputChannelInterface.SetTitleAndTooltip(
"IR",
"Demodulated IR receiver output (e.g. TSOP: idle HIGH, active LOW)");
mInputChannelInterface.SetChannel(mInputChannel);
AddInterface(&mInputChannelInterface);
AddExportOption(0, "Export as text/csv file");
AddExportExtension(0, "text", "txt");
AddExportExtension(0, "csv", "csv");
ClearChannels();
AddChannel(mInputChannel, "IR", false);
}
IrFoxAnalyzerSettings::~IrFoxAnalyzerSettings()
{
}
bool IrFoxAnalyzerSettings::SetSettingsFromInterfaces()
{
mInputChannel = mInputChannelInterface.GetChannel();
ClearChannels();
AddChannel(mInputChannel, "IR Fox", true);
return true;
}
void IrFoxAnalyzerSettings::UpdateInterfacesFromSettings()
{
mInputChannelInterface.SetChannel(mInputChannel);
}
void IrFoxAnalyzerSettings::LoadSettings(const char* settings)
{
SimpleArchive text_archive;
text_archive.SetString(settings);
text_archive >> mInputChannel;
ClearChannels();
AddChannel(mInputChannel, "IR Fox", true);
UpdateInterfacesFromSettings();
}
const char* IrFoxAnalyzerSettings::SaveSettings()
{
SimpleArchive text_archive;
text_archive << mInputChannel;
return SetReturnString(text_archive.GetString());
}

View File

@ -1,24 +0,0 @@
#ifndef IRFOX_ANALYZER_SETTINGS
#define IRFOX_ANALYZER_SETTINGS
#include <AnalyzerSettings.h>
#include <AnalyzerTypes.h>
class IrFoxAnalyzerSettings : public AnalyzerSettings
{
public:
IrFoxAnalyzerSettings();
virtual ~IrFoxAnalyzerSettings();
virtual bool SetSettingsFromInterfaces();
void UpdateInterfacesFromSettings();
virtual void LoadSettings(const char* settings);
virtual const char* SaveSettings();
Channel mInputChannel;
protected:
AnalyzerSettingInterfaceChannel mInputChannelInterface;
};
#endif

View File

@ -1,593 +0,0 @@
#include "IrFoxDecoder.h"
#include <AnalyzerResults.h>
#include <algorithm>
#include <cstdio>
#include <cmath>
#include <cstring>
void IrFoxDecoder::reset()
{
*this = IrFoxDecoder{};
rise_sync_time_us = irfox::kBitTimeUs;
next_control_bit = irfox::kBitPerByte;
have_last_processed = false;
last_processed_edge_us = 0;
}
uint16_t IrFoxDecoder::ceil_div_u16(uint16_t val, uint16_t divider)
{
if (divider == 0)
return 0;
int ret = val / divider;
if ((val << 4) / divider - (ret << 4) >= 8)
ret++;
return static_cast<uint16_t>(ret);
}
uint8_t IrFoxDecoder::crc8(const uint8_t* data, uint8_t start, uint8_t end, uint8_t poly)
{
uint8_t crc = 0xff;
for (size_t i = start; i < end; i++)
{
crc ^= data[i];
for (size_t j = 0; j < 8; j++)
{
if ((crc & 0x80) != 0)
crc = static_cast<uint8_t>((crc << 1) ^ poly);
else
crc <<= 1;
}
}
return crc;
}
bool IrFoxDecoder::crc_check(uint8_t len, uint16_t& crc_out)
{
crc_out = 0;
crc_out = static_cast<uint16_t>(static_cast<uint16_t>(crc8(data_buffer, 0, len, irfox::kPoly1) << 8) & 0xFF00u);
crc_out = static_cast<uint16_t>(crc_out | (crc8(data_buffer, 0, static_cast<uint8_t>(len + 1), irfox::kPoly2) & 0xFFu));
const bool ok = (data_buffer[len] == static_cast<uint8_t>((crc_out >> 8) & 0xFF)) &&
(data_buffer[len + 1] == static_cast<uint8_t>(crc_out & 0xFF));
return ok;
}
void IrFoxDecoder::first_rx()
{
err_low_signal = err_high_signal = err_other = 0;
pack_size = 0;
is_buffer_overflow = false;
is_available = false;
buf_bit_pos = 0;
is_data = true;
i_data_buffer = 0;
next_control_bit = irfox::kBitPerByte;
i_sync_bit = 0;
err_sync_bit = 0;
is_wrong_pack = false;
is_preamb = true;
is_recive = false;
is_recive_raw = false;
msg_type_receive = 0;
rise_sync_time_us = irfox::kBitTimeUs;
std::memset(data_buffer, 0, sizeof data_buffer);
preamble_bubble_start_valid_ = false;
trim_first_data_bit_cell_ = false;
}
void IrFoxDecoder::listen_start(double t_us)
{
const uint32_t irmax = irfox::irTimeoutUs(rise_sync_time_us);
// Как IR_DecoderRaw::listenStart: пауза по lastEdgeTime, не по prevRise.
if (is_recive_raw && last_edge_time_us > 0.0 && (t_us - last_edge_time_us) > irmax * 2.0)
{
is_recive_raw = false;
first_rx();
}
}
void IrFoxDecoder::check_timeout(double t_us)
{
if (!is_recive)
return;
const uint32_t irmax = irfox::irTimeoutUs(rise_sync_time_us);
if (t_us - last_edge_time_us > irmax * 2.0)
{
// Как IR_DecoderRaw::checkTimeout после фикса: полный сброс, иначе залипание FSM.
is_recive = false;
msg_type_receive = 0;
is_recive_raw = false;
first_rx();
// Не last_edge_time_us = t_us: как IR_DecoderRaw — не расходить с «хвостом» фронтов.
}
}
void IrFoxDecoder::write_to_buffer(bool bit, bool pack_trace_invert_fix, uint64_t cell_start_s, uint64_t cell_end_s,
const IrFoxOnBit& on_bit, const IrFoxOnPacket& on_pkt, IrFoxEmitBitMode emit_mode)
{
if (i_data_buffer > irfox::kDataByteSizeMax * 8u)
{
if (!is_buffer_overflow && on_bit)
{
IrFoxEmitBit e{};
e.start_sample = static_cast<int64_t>(cell_start_s);
e.end_sample = static_cast<int64_t>(cell_end_s);
e.frame_type = IRF_FT_OVERFLOW;
e.mflags = DISPLAY_AS_ERROR_FLAG;
fill_err_snapshot(e);
std::strncpy(e.bubble_text, "OVF", sizeof e.bubble_text);
e.bubble_text[sizeof e.bubble_text - 1] = '\0';
on_bit(e);
}
is_buffer_overflow = true;
}
if (is_buffer_overflow || is_preamb || is_wrong_pack)
{
// Как IR_DecoderRaw::writeToBuffer: полный first_rx() вместо только сброса флагов приёма.
first_rx();
return;
}
if (buf_bit_pos == next_control_bit)
{
next_control_bit = next_control_bit + (is_data ? irfox::kSyncBits : irfox::kBitPerByte);
is_data = !is_data;
i_sync_bit = 0;
err_sync_bit = 0;
}
if (is_data)
{
const bool was_first_data_bit = (i_data_buffer == 0);
data_buffer[i_data_buffer / 8] |= static_cast<uint8_t>(bit ? 1 : 0) << (7 - (i_data_buffer % 8));
i_data_buffer++;
buf_bit_pos++;
uint8_t fl = 0;
if (pack_trace_invert_fix)
fl |= DISPLAY_AS_WARNING_FLAG;
if (on_bit && emit_mode == IrFoxEmitBitMode::WithBubble)
{
IrFoxEmitBit e{static_cast<int64_t>(cell_start_s), static_cast<int64_t>(cell_end_s), IRF_FT_DATA_BIT,
bit ? 1u : 0u, static_cast<uint64_t>(i_data_buffer - 1), fl, pack_trace_invert_fix, 0, 0, 0};
fill_err_snapshot(e);
e.bubble_text[0] = static_cast<char>(bit ? '1' : '0');
e.bubble_text[1] = '\0';
on_bit(e);
}
if (was_first_data_bit && trim_first_data_bit_cell_)
trim_first_data_bit_cell_ = false;
}
else
{
if (i_sync_bit == 0)
{
const bool last_data_bit =
(data_buffer[((i_data_buffer - 1) / 8)] >> (7 - ((i_data_buffer - 1) % 8))) & 1;
if (bit != static_cast<bool>(last_data_bit))
{
buf_bit_pos++;
i_sync_bit++;
if (on_bit && emit_mode == IrFoxEmitBitMode::WithBubble)
{
IrFoxEmitBit e{static_cast<int64_t>(cell_start_s), static_cast<int64_t>(cell_end_s), IRF_FT_SYNC_BIT,
bit ? 1u : 0u, static_cast<uint64_t>(buf_bit_pos), 0, false, 0, 0, 0};
fill_err_snapshot(e);
std::snprintf(e.bubble_text, sizeof e.bubble_text, "s: %c", bit ? '1' : '0');
on_bit(e);
}
}
else
{
i_sync_bit = 0;
err_other++;
err_sync_bit++;
const bool fatal_sync = (err_sync_bit >= irfox::kSyncBits);
if (fatal_sync)
is_wrong_pack = true;
if (on_bit && fatal_sync)
{
IrFoxEmitBit e{static_cast<int64_t>(cell_start_s), static_cast<int64_t>(cell_end_s), IRF_FT_ABORT,
0, 0, DISPLAY_AS_ERROR_FLAG, false, 0, 0, 0};
fill_err_snapshot(e);
std::strncpy(e.bubble_text, "SYNC!", sizeof e.bubble_text);
e.bubble_text[sizeof e.bubble_text - 1] = '\0';
on_bit(e);
}
}
}
else
{
buf_bit_pos++;
i_sync_bit++;
if (on_bit && emit_mode == IrFoxEmitBitMode::WithBubble)
{
IrFoxEmitBit e{static_cast<int64_t>(cell_start_s), static_cast<int64_t>(cell_end_s), IRF_FT_SYNC_BIT,
bit ? 1u : 0u, static_cast<uint64_t>(buf_bit_pos), 0, false, 0, 0, 0};
fill_err_snapshot(e);
std::snprintf(e.bubble_text, sizeof e.bubble_text, "s: %c", bit ? '1' : '0');
on_bit(e);
}
}
is_wrong_pack = (err_sync_bit >= irfox::kSyncBits);
}
if (!is_available && is_data && !is_wrong_pack)
{
if (i_data_buffer == 8 * irfox::kMsgBytes)
pack_size = static_cast<uint16_t>(data_buffer[0] & 0x1Fu);
if (pack_size && (i_data_buffer == 8))
msg_type_receive = static_cast<uint8_t>((data_buffer[0] >> 5) | 0xF8u);
if (pack_size && (i_data_buffer == pack_size * irfox::kBitPerByte))
{
uint16_t crc_computed = 0;
const bool crc_ok = crc_check(static_cast<uint8_t>(pack_size - irfox::kCrcBytes), crc_computed);
crc_value = crc_computed;
is_recive = false;
is_recive_raw = false;
msg_type_receive = 0;
is_available = crc_ok;
IrFoxEmitPacket pkt{};
pkt.start_sample = static_cast<int64_t>(cell_start_s);
pkt.end_sample = static_cast<int64_t>(cell_end_s);
pkt.crc_ok = crc_ok;
pkt.pack_size = static_cast<uint8_t>(pack_size);
pkt.err_low = err_low_signal;
pkt.err_high = err_high_signal;
pkt.err_other = err_other;
if (pack_size > 0 && pack_size <= irfox::kDataByteSizeMax)
std::memcpy(pkt.data_bytes, data_buffer, pack_size);
if (on_pkt)
on_pkt(pkt);
}
}
}
void IrFoxDecoder::processEdge(uint64_t sample, bool rising, uint32_t fs, const IrFoxOnBit& on_bit,
const IrFoxOnPacket& on_pkt)
{
const double t_us = sample_to_us(sample, fs);
const uint32_t irmax = irfox::irTimeoutUs(rise_sync_time_us);
uint32_t rise_min_us = rise_sync_time_us > irfox::kToleranceUs ? rise_sync_time_us - irfox::kToleranceUs : 0U;
listen_start(t_us);
// Как IR_DecoderRaw: пауза между фронтами по lastEdgeTime при активном приёме кадра.
if (last_edge_time_us > 0.0 && (t_us - last_edge_time_us) > irmax * 2.0 && is_recive)
check_timeout(t_us);
last_edge_time_us = t_us;
last_edge_sample = sample;
const uint32_t rise_max_us = rise_sync_time_us + irfox::kToleranceUs;
/** Визуализация: начало PRE с ближайшего спада в пределах ~3 битовых периодов (ИК-метка). */
auto new_bubble_preamble_start = [&](uint64_t edge_s, bool is_rising) -> uint64_t {
if (!is_rising)
return edge_s;
if (edge_s > prev_fall_sample)
{
const double span_us = double(edge_s - prev_fall_sample) * 1e6 / double(fs);
const double max_us = double(rise_max_us) * 3.0;
if (span_us <= max_us)
return prev_fall_sample;
}
return edge_s;
};
if (rising)
{
const double delta_rp = t_us - prev_rise_us;
const uint32_t cand_rp = static_cast<uint32_t>(delta_rp);
const uint32_t cand_ht = static_cast<uint32_t>(t_us - prev_fall_us);
const uint32_t cand_lt = static_cast<uint32_t>(prev_fall_us - prev_rise_us);
#if IRFOX_SHORT_LOW_GLITCH_REJECT
const bool short_low_glitch =
is_recive && !is_preamb && cand_ht < (rise_min_us / 8U) && cand_lt >= rise_min_us &&
cand_rp >= rise_min_us && cand_rp <= irmax;
if (short_low_glitch)
{
err_other++;
irfox::irfoxGlitchPhaseNudgeUs(t_us, rise_sync_time_us, prev_rise_us);
last_processed_edge_us = t_us;
have_last_processed = true;
return;
}
#endif
#if IRFOX_MICRO_GAP_RISE_REJECT
const bool micro_gap_cand_lt_ok =
(cand_lt >= rise_min_us) || (cand_lt >= (rise_min_us / 4U) && cand_lt < rise_min_us);
const bool micro_gap_rise = is_recive && !is_preamb && cand_ht < (rise_min_us / 8U) && micro_gap_cand_lt_ok &&
cand_rp >= (rise_min_us / 4U) && cand_rp < rise_min_us && cand_rp <= irmax;
if (micro_gap_rise)
{
err_other++;
irfox::irfoxGlitchPhaseNudgeUs(t_us, rise_sync_time_us, prev_rise_us);
last_processed_edge_us = t_us;
have_last_processed = true;
return;
}
#endif
if (cand_rp <= rise_max_us / 4U && !high_count && !low_count)
{
err_other++;
last_processed_edge_us = t_us;
have_last_processed = true;
return;
}
// Визуализация PRE: длинная пауза, первый подъём — якорь от спада метки (декод как STM32DMA).
if (cand_rp > irmax * 2U && !is_recive_raw)
{
preamble_bubble_start_sample_ = new_bubble_preamble_start(sample, true);
preamble_bubble_start_valid_ = true;
}
const bool accept_rise_timing =
(delta_rp > static_cast<double>(rise_max_us) / 4.0) || high_count != 0 || low_count != 0;
if (accept_rise_timing)
{
rise_period_anchor_sample_ = prev_rise_sample;
rise_period_us = cand_rp;
high_time_us = cand_ht;
low_time_us = cand_lt;
prev_rise_us = t_us;
prev_rise_sample = sample;
}
else
{
err_other++;
}
}
else
{
if (t_us - prev_fall_us > rise_min_us / 4.0)
{
prev_fall_us = t_us;
prev_fall_sample = sample;
}
else
{
err_other++;
}
}
// Как IR_DecoderRaw::tick: после длинной паузы старт сырого приёма (без отдельного firstRX — флаги ниже).
if (t_us > prev_rise_us && (t_us - prev_rise_us) > irmax * 2.0 && !is_recive_raw)
{
preamb_front_counter = static_cast<int8_t>(irfox::kPreambFronts - 1);
is_preamb = true;
is_recive = true;
is_recive_raw = true;
is_wrong_pack = false;
if (!preamble_bubble_start_valid_)
{
preamble_bubble_start_sample_ = new_bubble_preamble_start(sample, rising);
preamble_bubble_start_valid_ = true;
}
}
if (preamb_front_counter)
{
if (rising && rise_period_us < irmax)
{
if (rise_period_us < rise_min_us / 2U)
{
preamb_front_counter += 2;
err_other++;
}
}
preamb_front_counter--;
}
else
{
if (is_preamb)
{
is_preamb = false;
// IR_DecoderRaw: prevRise += risePeriod / 2 — фаза как в прошивке.
// Бабл PRE: до текущего фронта (sample1), чтобы охватить все kPreambPulse периодов (3 импульса),
// а не только до предыдущего подъёма (~2 периода).
const uint64_t preamble_bubble_end_sample = sample > 0 ? sample - 1 : sample;
prev_rise_us += rise_period_us / 2.0;
{
const double half_us = 0.5 * static_cast<double>(rise_period_us);
const uint64_t half_s = static_cast<uint64_t>(std::llround(half_us * double(fs) / 1e6));
prev_rise_sample += half_s;
}
trim_first_data_bit_cell_ = true;
if (on_bit && preamble_bubble_start_valid_)
{
int64_t pe_start = static_cast<int64_t>(preamble_bubble_start_sample_);
int64_t pe_end = static_cast<int64_t>(preamble_bubble_end_sample);
if (preamble_bubble_end_sample == 0 || pe_end < pe_start)
pe_end = static_cast<int64_t>(sample > 0 ? sample - 1 : sample);
IrFoxEmitBit pe{};
pe.start_sample = pe_start;
pe.end_sample = pe_end;
pe.frame_type = IRF_FT_PREAMBLE;
fill_err_snapshot(pe);
std::strncpy(pe.bubble_text, "PRE", sizeof pe.bubble_text);
pe.bubble_text[sizeof pe.bubble_text - 1] = '\0';
on_bit(pe);
}
preamble_bubble_start_valid_ = false;
last_processed_edge_us = t_us;
have_last_processed = true;
return;
}
}
if (is_preamb)
{
last_processed_edge_us = t_us;
have_last_processed = true;
return;
}
if (rise_period_us > irmax || is_buffer_overflow || rise_period_us < rise_min_us || is_wrong_pack)
{
last_processed_edge_us = t_us;
have_last_processed = true;
return;
}
if (rising)
{
high_count = low_count = all_count = 0;
bool invert_err = false;
uint64_t cell_start_s = rise_period_anchor_sample_;
const uint64_t cell_end_s = sample > 0 ? sample - 1 : sample;
// После prev_rise += half period якорь может оказаться близко к текущему подъёму;
// max(anchor, prev_fall) > cell_end даёт пустой интервал — бабл первого бита пропадает.
if (trim_first_data_bit_cell_ && is_data && i_data_buffer == 0)
{
const uint64_t trimmed = std::max(cell_start_s, prev_fall_sample);
if (trimmed <= cell_end_s)
cell_start_s = trimmed;
}
if (irfox::aroundRisePeriod(rise_period_us, rise_sync_time_us))
{
if (high_time_us > low_time_us)
write_to_buffer(true, false, cell_start_s, cell_end_s, on_bit, on_pkt, IrFoxEmitBitMode::WithBubble);
else
write_to_buffer(false, false, cell_start_s, cell_end_s, on_bit, on_pkt, IrFoxEmitBitMode::WithBubble);
}
else
{
uint16_t hc = ceil_div_u16(static_cast<uint16_t>(high_time_us > 0xFFFF ? 0xFFFF : high_time_us),
static_cast<uint16_t>(rise_sync_time_us));
uint16_t lc = ceil_div_u16(static_cast<uint16_t>(low_time_us > 0xFFFF ? 0xFFFF : low_time_us),
static_cast<uint16_t>(rise_sync_time_us));
uint16_t ac = ceil_div_u16(static_cast<uint16_t>(rise_period_us > 0xFFFF ? 0xFFFF : rise_period_us),
static_cast<uint16_t>(rise_sync_time_us));
high_count = static_cast<int8_t>(hc > 127 ? 127 : hc);
low_count = static_cast<int8_t>(lc > 127 ? 127 : lc);
all_count = static_cast<int8_t>(ac > 127 ? 127 : ac);
if (high_count == 0 && high_time_us > rise_sync_time_us / 3U)
{
high_count++;
err_other++;
}
if (low_count + high_count > all_count)
{
if (low_count > high_count)
{
low_count = static_cast<int8_t>(all_count - high_count);
err_low_signal = static_cast<uint8_t>(err_low_signal + static_cast<uint8_t>(low_count));
}
else if (low_count < high_count)
{
high_count = static_cast<int8_t>(all_count - low_count);
err_high_signal = static_cast<uint8_t>(err_high_signal + static_cast<uint8_t>(high_count));
}
else if (low_count == high_count)
{
invert_err = true;
err_other = static_cast<uint8_t>(err_other + static_cast<uint8_t>(all_count));
}
}
if (low_count < high_count)
err_high_signal = static_cast<uint8_t>(err_high_signal + static_cast<uint8_t>(high_count));
else
err_low_signal = static_cast<uint8_t>(err_low_signal + static_cast<uint8_t>(low_count));
const bool burst_is_data_start = is_data;
const uint64_t merge_bit_index =
burst_is_data_start ? static_cast<uint64_t>(i_data_buffer) : static_cast<uint64_t>(buf_bit_pos + 1);
char s_bits[20]{};
char d_bits[20]{};
size_t s_n = 0;
size_t d_n = 0;
int first_merge_bit = -1;
bool merge_warn = false;
auto append_merge = [&](bool as_data, bool bitv) {
if (first_merge_bit < 0)
first_merge_bit = bitv ? 1 : 0;
char* buf = as_data ? d_bits : s_bits;
size_t& n = as_data ? d_n : s_n;
if (n + 1 < sizeof s_bits)
buf[n++] = static_cast<char>(bitv ? '1' : '0');
};
auto emit_merge_if_needed = [&]() {
if ((s_n == 0 && d_n == 0) || !on_bit)
return;
IrFoxEmitBit e{};
e.start_sample = static_cast<int64_t>(cell_start_s);
e.end_sample = static_cast<int64_t>(cell_end_s);
e.frame_type = (d_n > 0) ? IRF_FT_DATA_BIT : IRF_FT_SYNC_BIT;
e.bit_value = (first_merge_bit > 0) ? 1u : 0u;
e.bit_index = merge_bit_index;
e.mflags = merge_warn ? DISPLAY_AS_WARNING_FLAG : 0;
e.invert_fix = merge_warn;
fill_err_snapshot(e);
s_bits[s_n] = '\0';
d_bits[d_n] = '\0';
if (s_n && d_n)
std::snprintf(e.bubble_text, sizeof e.bubble_text, "s: %s d: %s", s_bits, d_bits);
else if (s_n)
std::snprintf(e.bubble_text, sizeof e.bubble_text, "s: %s", s_bits);
else
std::memcpy(e.bubble_text, d_bits, d_n + 1);
on_bit(e);
};
for (int8_t i = 0; i < low_count && 8 - i; i++)
{
const bool row_is_data = is_data;
if (i == low_count - 1 && invert_err)
{
invert_err = false;
write_to_buffer(true, true, cell_start_s, cell_end_s, on_bit, on_pkt, IrFoxEmitBitMode::Quiet);
merge_warn = true;
append_merge(row_is_data, true);
}
else
{
write_to_buffer(false, false, cell_start_s, cell_end_s, on_bit, on_pkt, IrFoxEmitBitMode::Quiet);
append_merge(row_is_data, false);
}
}
for (int8_t i = 0; i < high_count && 8 - i; i++)
{
const bool row_is_data = is_data;
if (i == high_count - 1 && invert_err)
{
invert_err = false;
write_to_buffer(false, true, cell_start_s, cell_end_s, on_bit, on_pkt, IrFoxEmitBitMode::Quiet);
merge_warn = true;
append_merge(row_is_data, false);
}
else
{
write_to_buffer(true, false, cell_start_s, cell_end_s, on_bit, on_pkt, IrFoxEmitBitMode::Quiet);
append_merge(row_is_data, true);
}
}
emit_merge_if_needed();
}
}
last_processed_edge_us = t_us;
have_last_processed = true;
}
void IrFoxDecoder::flushEnd(uint64_t last_sample, uint32_t fs, const IrFoxOnBit& on_bit, const IrFoxOnPacket& on_pkt)
{
const double t_us = sample_to_us(last_sample, fs);
listen_start(t_us);
check_timeout(t_us);
(void)on_bit;
(void)on_pkt;
}

View File

@ -1,135 +0,0 @@
#pragma once
#include "IrFoxProtocolConstants.h"
#include <cstdint>
#include <functional>
enum IrFoxFrameType : uint8_t
{
IRF_FT_DATA_BIT = 1,
IRF_FT_SYNC_BIT = 2,
IRF_FT_PACKET_OK = 3,
IRF_FT_PACKET_CRC_FAIL = 4,
IRF_FT_OVERFLOW = 5,
IRF_FT_ABORT = 6,
IRF_FT_PREAMBLE = 7,
};
/** WithBubble — вызвать on_bit; Quiet — только обновить состояние (для пакета битов с одного фронта). */
enum class IrFoxEmitBitMode : uint8_t
{
WithBubble,
Quiet,
};
struct IrFoxEmitBit
{
int64_t start_sample;
int64_t end_sample;
uint8_t frame_type;
uint64_t bit_value;
uint64_t bit_index;
uint8_t mflags;
bool invert_fix;
uint8_t err_low;
uint8_t err_high;
uint8_t err_other;
/** Подпись бабла: "0", "1" или склейка "001"; пусто — смотреть bit_value. */
char bubble_text[32]{};
};
struct IrFoxEmitPacket
{
int64_t start_sample;
int64_t end_sample;
bool crc_ok;
uint8_t pack_size;
uint8_t err_low;
uint8_t err_high;
uint8_t err_other;
uint8_t data_bytes[irfox::kDataByteSizeMax];
};
using IrFoxOnBit = std::function<void(const IrFoxEmitBit&)>;
using IrFoxOnPacket = std::function<void(const IrFoxEmitPacket&)>;
class IrFoxDecoder
{
public:
void reset();
void processEdge(uint64_t sample, bool rising, uint32_t sample_rate_hz, const IrFoxOnBit& on_bit,
const IrFoxOnPacket& on_pkt);
void flushEnd(uint64_t last_sample, uint32_t sample_rate_hz, const IrFoxOnBit& on_bit, const IrFoxOnPacket& on_pkt);
private:
static uint16_t ceil_div_u16(uint16_t val, uint16_t divider);
static uint8_t crc8(const uint8_t* data, uint8_t start, uint8_t end, uint8_t poly);
bool crc_check(uint8_t len, uint16_t& crc_out);
void first_rx();
void listen_start(double t_us);
void check_timeout(double t_us);
void write_to_buffer(bool bit, bool pack_trace_invert_fix, uint64_t cell_start_s, uint64_t cell_end_s,
const IrFoxOnBit& on_bit, const IrFoxOnPacket& on_pkt,
IrFoxEmitBitMode emit_mode = IrFoxEmitBitMode::WithBubble);
double sample_to_us(uint64_t sample, uint32_t fs) const { return double(sample) * 1e6 / double(fs); }
// --- state (mirror IR_DecoderRaw) ---
uint8_t data_buffer[irfox::kDataByteSizeMax]{};
uint8_t err_low_signal = 0;
uint8_t err_high_signal = 0;
uint8_t err_other = 0;
bool is_available = false;
uint16_t pack_size = 0;
uint16_t crc_value = 0;
bool is_recive = false;
bool is_recive_raw = false;
bool is_preamb = false;
bool is_buffer_overflow = false;
bool is_wrong_pack = false;
uint32_t rise_sync_time_us = irfox::kBitTimeUs;
double prev_rise_us = 0;
double prev_fall_us = 0;
uint64_t prev_rise_sample = 0;
uint64_t prev_fall_sample = 0;
/** Сэмпл предыдущего нарастающего фронта до обновления на текущем тике (граница ячейки бита, см. IR_DecoderRaw::tick). */
uint64_t rise_period_anchor_sample_ = 0;
uint64_t preamble_bubble_start_sample_ = 0;
bool preamble_bubble_start_valid_ = false;
bool trim_first_data_bit_cell_ = false;
double last_edge_time_us = 0;
uint64_t last_edge_sample = 0;
double last_processed_edge_us = 0;
bool have_last_processed = false;
void fill_err_snapshot(IrFoxEmitBit& e) const
{
e.err_low = err_low_signal;
e.err_high = err_high_signal;
e.err_other = err_other;
}
uint32_t rise_period_us = 0;
uint32_t high_time_us = 0;
uint32_t low_time_us = 0;
int8_t high_count = 0;
int8_t low_count = 0;
int8_t all_count = 0;
uint16_t wrong_counter = 0;
int8_t preamb_front_counter = 0;
int16_t buf_bit_pos = 0;
bool is_data = true;
uint16_t i_data_buffer = 0;
uint16_t next_control_bit = irfox::kBitPerByte;
uint8_t i_sync_bit = 0;
uint8_t err_sync_bit = 0;
uint16_t error_counter = 0;
uint8_t msg_type_receive = 0;
};

View File

@ -1,71 +0,0 @@
#pragma once
#include <cstdint>
namespace irfox {
constexpr uint32_t kCarrierPeriodUs = 1000000U / 38000U;
constexpr uint32_t kBitActiveTakts = 25U;
constexpr uint32_t kBitPauseTakts = 12U;
constexpr uint32_t kBitTakts = kBitActiveTakts + kBitPauseTakts;
constexpr uint32_t kBitTimeUs = kBitTakts * kCarrierPeriodUs;
constexpr uint32_t kToleranceUs = 300U;
/** Мин. длительность плато (мкс) для потокового анти-глитча в анализаторе; согласовано с IR_INPUT_MIN_PULSE_US. */
constexpr uint32_t kMinFilteredPulseUs = 10U;
constexpr uint8_t kBitPerByte = 8U;
constexpr uint8_t kMsgBytes = 1;
constexpr uint8_t kAddrBytes = 2;
constexpr uint8_t kCrcBytes = 2;
constexpr uint8_t kPoly1 = 0x31;
constexpr uint8_t kPoly2 = 0x8C;
constexpr uint8_t kSyncBits = 3U;
constexpr uint8_t kBytePerPack = 31;
constexpr uint8_t kDataByteSizeMax =
static_cast<uint8_t>(kMsgBytes + kAddrBytes + kAddrBytes + kBytePerPack + kCrcBytes);
constexpr uint8_t kPreambPulse = 3;
constexpr uint8_t kPreambFronts = kPreambPulse * 2U;
/** Отброс ложного подъёма после микро-LOW в паузе; зеркало IR_config.h (прошивка). */
#ifndef IRFOX_SHORT_LOW_GLITCH_REJECT
#define IRFOX_SHORT_LOW_GLITCH_REJECT 1
#endif
#ifndef IRFOX_GLITCH_REJECT_PHASE_NUDGE
#define IRFOX_GLITCH_REJECT_PHASE_NUDGE 1
#endif
#ifndef IRFOX_MICRO_GAP_RISE_REJECT
#define IRFOX_MICRO_GAP_RISE_REJECT 1
#endif
inline uint32_t irTimeoutUs(uint32_t riseSyncTimeUs)
{
const uint32_t riseMax = riseSyncTimeUs + kToleranceUs;
return riseMax * (8U + kSyncBits + 1U);
}
/** Как IR_DecoderRaw.h: aroundRise(t) → riseTimeMin < t && t < riseTimeMax (ветка STM32DMA). */
inline bool aroundRisePeriod(uint32_t periodUs, uint32_t riseSyncTimeUs)
{
const uint32_t lo = riseSyncTimeUs > kToleranceUs ? riseSyncTimeUs - kToleranceUs : 0U;
const uint32_t hi = riseSyncTimeUs + kToleranceUs;
return lo < periodUs && periodUs < hi;
}
inline void irfoxGlitchPhaseNudgeUs(double edge_us, uint32_t rise_sync_us, double& prev_rise_us)
{
#if IRFOX_GLITCH_REJECT_PHASE_NUDGE
if (!(edge_us > static_cast<double>(rise_sync_us)))
return;
const double nudged = edge_us - static_cast<double>(rise_sync_us);
if (nudged > prev_rise_us && nudged < edge_us)
prev_rise_us = nudged;
#else
(void)edge_us;
(void)rise_sync_us;
(void)prev_rise_us;
#endif
}
} // namespace irfox

View File

@ -1,67 +0,0 @@
#include "IrFoxSimulationDataGenerator.h"
#include "IrFoxAnalyzerSettings.h"
#include <AnalyzerHelpers.h>
IrFoxSimulationDataGenerator::IrFoxSimulationDataGenerator()
{
}
IrFoxSimulationDataGenerator::~IrFoxSimulationDataGenerator()
{
}
void IrFoxSimulationDataGenerator::Initialize(U32 simulation_sample_rate, IrFoxAnalyzerSettings* settings)
{
mSimulationSampleRateHz = simulation_sample_rate;
mSettings = settings;
mIrSimulationData.SetChannel(mSettings->mInputChannel);
mIrSimulationData.SetSampleRate(simulation_sample_rate);
// Как у «покоя» на выходе TSOP: линия подтянута вверх
mIrSimulationData.SetInitialBitState(BIT_HIGH);
}
void IrFoxSimulationDataGenerator::EmitIdle(U32 samples)
{
mIrSimulationData.Advance(samples);
}
void IrFoxSimulationDataGenerator::EmitLow(U32 samples)
{
mIrSimulationData.TransitionIfNeeded(BIT_LOW);
mIrSimulationData.Advance(samples);
}
void IrFoxSimulationDataGenerator::EmitHigh(U32 samples)
{
mIrSimulationData.TransitionIfNeeded(BIT_HIGH);
mIrSimulationData.Advance(samples);
}
U32 IrFoxSimulationDataGenerator::GenerateSimulationData(U64 largest_sample_requested, U32 sample_rate,
SimulationChannelDescriptor** simulation_channel)
{
const U64 adjusted_largest_sample_requested =
AnalyzerHelpers::AdjustSimulationTargetSample(largest_sample_requested, sample_rate, mSimulationSampleRateHz);
// Упрощённый «пакет»: несколько импульсов вниз (активный уровень приёмника).
while (mIrSimulationData.GetCurrentSampleNumber() < adjusted_largest_sample_requested)
{
const U32 us_to_samples = mSimulationSampleRateHz / 1000000;
if (us_to_samples == 0)
break;
EmitIdle(500 * us_to_samples);
EmitLow(4500 * us_to_samples);
EmitHigh(4500 * us_to_samples);
EmitLow(4500 * us_to_samples);
EmitHigh(4500 * us_to_samples);
EmitLow(560 * us_to_samples);
EmitHigh(560 * us_to_samples);
EmitLow(560 * us_to_samples);
EmitHigh(20000 * us_to_samples);
}
*simulation_channel = &mIrSimulationData;
return 1;
}

View File

@ -1,27 +0,0 @@
#ifndef IRFOX_SIMULATION_DATA_GENERATOR
#define IRFOX_SIMULATION_DATA_GENERATOR
#include <SimulationChannelDescriptor.h>
class IrFoxAnalyzerSettings;
class IrFoxSimulationDataGenerator
{
public:
IrFoxSimulationDataGenerator();
~IrFoxSimulationDataGenerator();
void Initialize(U32 simulation_sample_rate, IrFoxAnalyzerSettings* settings);
U32 GenerateSimulationData(U64 newest_sample_requested, U32 sample_rate, SimulationChannelDescriptor** simulation_channel);
protected:
IrFoxAnalyzerSettings* mSettings;
U32 mSimulationSampleRateHz;
SimulationChannelDescriptor mIrSimulationData;
void EmitIdle(U32 samples);
void EmitLow(U32 samples);
void EmitHigh(U32 samples);
};
#endif

View File

@ -1,52 +0,0 @@
name: Build
on:
push:
branches: [master, main]
tags:
- "*"
pull_request:
branches: [master, main]
jobs:
windows:
runs-on: windows-latest
steps:
- uses: actions/checkout@v4
- name: Build
run: |
cmake -B ${{github.workspace}}/Analyzer/raw/PulseLengthStat/build -S ${{github.workspace}}/Analyzer/raw/PulseLengthStat -A x64
cmake --build ${{github.workspace}}/Analyzer/raw/PulseLengthStat/build --config Release
- uses: actions/upload-artifact@v4
with:
name: windows
path: ${{github.workspace}}/Analyzer/raw/dll/*.dll
macos:
runs-on: macos-latest
steps:
- uses: actions/checkout@v4
- name: Build
run: |
cmake -B ${{github.workspace}}/Analyzer/raw/PulseLengthStat/build -S ${{github.workspace}}/Analyzer/raw/PulseLengthStat -DCMAKE_BUILD_TYPE=Release
cmake --build ${{github.workspace}}/Analyzer/raw/PulseLengthStat/build
- uses: actions/upload-artifact@v4
with:
name: macos
path: ${{github.workspace}}/Analyzer/raw/dll/*.so
linux:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Build
run: |
cmake -B ${{github.workspace}}/Analyzer/raw/PulseLengthStat/build -S ${{github.workspace}}/Analyzer/raw/PulseLengthStat -DCMAKE_BUILD_TYPE=Release
cmake --build ${{github.workspace}}/Analyzer/raw/PulseLengthStat/build
env:
CC: gcc-10
CXX: g++-10
- uses: actions/upload-artifact@v4
with:
name: linux
path: ${{github.workspace}}/Analyzer/raw/dll/*.so

View File

@ -1,3 +0,0 @@
/build
/build-nmake
.DS_Store

View File

@ -1,24 +0,0 @@
cmake_minimum_required(VERSION 3.13)
project(PulseLengthStatAnalyzer)
add_definitions(-DLOGIC2)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake)
include(ExternalAnalyzerSDK)
set(SOURCES
src/PulseLengthStatAnalyzer.cpp
src/PulseLengthStatAnalyzer.h
src/PulseLengthStatAnalyzerResults.cpp
src/PulseLengthStatAnalyzerResults.h
src/PulseLengthStatAnalyzerSettings.cpp
src/PulseLengthStatAnalyzerSettings.h
src/PulseLengthStatSimulationDataGenerator.cpp
src/PulseLengthStatSimulationDataGenerator.h
)
add_analyzer_plugin(${PROJECT_NAME} SOURCES ${SOURCES})

View File

@ -1,49 +0,0 @@
{
"version": 3,
"cmakeMinimumRequired": {
"major": 3,
"minor": 19,
"patch": 0
},
"configurePresets": [
{
"name": "win-vs2022-x64",
"displayName": "Visual Studio 2022 (x64)",
"generator": "Visual Studio 17 2022",
"architecture": "x64",
"binaryDir": "${sourceDir}/build"
},
{
"name": "win-vs2019-x64",
"displayName": "Visual Studio 2019 (x64)",
"generator": "Visual Studio 16 2019",
"architecture": "x64",
"binaryDir": "${sourceDir}/build"
},
{
"name": "win-nmake-release",
"displayName": "NMake Release (x64 Native Tools Command Prompt)",
"generator": "NMake Makefiles",
"binaryDir": "${sourceDir}/build-nmake",
"cacheVariables": {
"CMAKE_BUILD_TYPE": "Release"
}
}
],
"buildPresets": [
{
"name": "win-release",
"configurePreset": "win-vs2022-x64",
"configuration": "Release"
},
{
"name": "win-release-vs2019",
"configurePreset": "win-vs2019-x64",
"configuration": "Release"
},
{
"name": "nmake-release",
"configurePreset": "win-nmake-release"
}
]
}

View File

@ -1,21 +0,0 @@
@echo off
setlocal EnableDelayedExpansion
cd /d "%~dp0"
if not exist build\CMakeCache.txt (
echo Run configure_msvc.bat first.
exit /b 1
)
set "VSWHERE=%ProgramFiles(x86)%\Microsoft Visual Studio\Installer\vswhere.exe"
for /f "usebackq tokens=*" %%i in (`"%VSWHERE%" -latest -products * -requires Microsoft.VisualStudio.Component.VC.Tools.x86.x64 -property installationPath`) do set "VSINSTALL=%%i"
if not defined VSINSTALL (
echo MSVC not found. Add C++ workload in Visual Studio Installer.
exit /b 1
)
call "!VSINSTALL!\Common7\Tools\VsDevCmd.bat" -arch=x64 -host_arch=x64
if errorlevel 1 exit /b 1
cmake --build build
pause
exit /b %ERRORLEVEL%

View File

@ -1,66 +0,0 @@
include(FetchContent)
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED YES)
if(NOT CMAKE_RUNTIME_OUTPUT_DIRECTORY OR NOT CMAKE_LIBRARY_OUTPUT_DIRECTORY)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin/)
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin/)
endif()
if(NOT TARGET Saleae::AnalyzerSDK)
FetchContent_Declare(
analyzersdk
GIT_REPOSITORY https://github.com/saleae/AnalyzerSDK.git
GIT_TAG master
GIT_SHALLOW True
GIT_PROGRESS True
)
FetchContent_GetProperties(analyzersdk)
if(NOT analyzersdk_POPULATED)
FetchContent_Populate(analyzersdk)
include(${analyzersdk_SOURCE_DIR}/AnalyzerSDKConfig.cmake)
if(APPLE OR WIN32)
get_target_property(analyzersdk_lib_location Saleae::AnalyzerSDK IMPORTED_LOCATION)
if(CMAKE_LIBRARY_OUTPUT_DIRECTORY)
file(COPY ${analyzersdk_lib_location} DESTINATION ${CMAKE_LIBRARY_OUTPUT_DIRECTORY})
else()
message(WARNING "Please define CMAKE_RUNTIME_OUTPUT_DIRECTORY and CMAKE_LIBRARY_OUTPUT_DIRECTORY if you want unit tests to locate ${analyzersdk_lib_location}")
endif()
endif()
endif()
endif()
# Shared folder for all Saleae LLA plugins in this repo: Analyzer/raw/dll
set(ANALYZER_DLL_OUT_DIR "${CMAKE_SOURCE_DIR}/../dll")
get_filename_component(ANALYZER_DLL_OUT_DIR "${ANALYZER_DLL_OUT_DIR}" ABSOLUTE)
file(MAKE_DIRECTORY "${ANALYZER_DLL_OUT_DIR}")
function(add_analyzer_plugin TARGET)
set(options)
set(single_value_args)
set(multi_value_args SOURCES)
cmake_parse_arguments(_p "${options}" "${single_value_args}" "${multi_value_args}" ${ARGN})
add_library(${TARGET} MODULE ${_p_SOURCES})
target_link_libraries(${TARGET} PRIVATE Saleae::AnalyzerSDK)
set(ANALYZER_DESTINATION "Analyzers")
install(TARGETS ${TARGET} RUNTIME DESTINATION ${ANALYZER_DESTINATION}
LIBRARY DESTINATION ${ANALYZER_DESTINATION})
set_target_properties(${TARGET} PROPERTIES
RUNTIME_OUTPUT_DIRECTORY "${ANALYZER_DLL_OUT_DIR}"
LIBRARY_OUTPUT_DIRECTORY "${ANALYZER_DLL_OUT_DIR}")
if(CMAKE_CONFIGURATION_TYPES)
foreach(CFG ${CMAKE_CONFIGURATION_TYPES})
string(TOUPPER ${CFG} CFG_UPPER)
set_target_properties(${TARGET} PROPERTIES
RUNTIME_OUTPUT_DIRECTORY_${CFG_UPPER} "${ANALYZER_DLL_OUT_DIR}"
LIBRARY_OUTPUT_DIRECTORY_${CFG_UPPER} "${ANALYZER_DLL_OUT_DIR}")
endforeach()
endif()
endfunction()

View File

@ -1,39 +0,0 @@
@echo off
setlocal EnableDelayedExpansion
cd /d "%~dp0"
echo === PulseLengthStatAnalyzer: configure with MSVC ===
echo.
set "VSWHERE=%ProgramFiles(x86)%\Microsoft Visual Studio\Installer\vswhere.exe"
if not exist "%VSWHERE%" (
echo [ERROR] vswhere not found. Install one of:
echo - Visual Studio 2022 with workload "Desktop development with C++"
echo - Build Tools for Visual Studio 2022: https://visualstudio.microsoft.com/visual-cpp-build-tools/
echo ^(select "Desktop development with C++" / MSVC, Windows SDK^)
exit /b 1
)
for /f "usebackq tokens=*" %%i in (`"%VSWHERE%" -latest -products * -requires Microsoft.VisualStudio.Component.VC.Tools.x86.x64 -property installationPath`) do set "VSINSTALL=%%i"
if not defined VSINSTALL (
echo [ERROR] MSVC toolset not found. Add "Desktop development with C++" in Visual Studio Installer.
exit /b 1
)
echo Found: !VSINSTALL!
call "!VSINSTALL!\Common7\Tools\VsDevCmd.bat" -arch=x64 -host_arch=x64
if errorlevel 1 exit /b 1
if exist build rmdir /s /q build
if exist build-nmake rmdir /s /q build-nmake
mkdir build
cd build
cmake .. -G "NMake Makefiles" -DCMAKE_BUILD_TYPE=Release
if errorlevel 1 exit /b 1
echo.
echo Configure OK. Build: build_msvc.bat ^(or from same VS env: cd build ^& cmake --build .^)
echo Output DLL: ..\dll\ ^(all analyzers share this folder^)
pause
exit /b 0

View File

@ -1,110 +0,0 @@
#include "PulseLengthStatAnalyzer.h"
#include "PulseLengthStatAnalyzerSettings.h"
#include <AnalyzerChannelData.h>
// One frame per stable level between edges. mData1 = duration in samples; mFlags: 1 = HIGH, 0 = LOW.
PulseLengthStatAnalyzer::PulseLengthStatAnalyzer()
: Analyzer2(),
mSettings(),
mSimulationInitilized(false)
{
SetAnalyzerSettings(&mSettings);
}
PulseLengthStatAnalyzer::~PulseLengthStatAnalyzer()
{
KillThread();
}
void PulseLengthStatAnalyzer::SetupResults()
{
mResults.reset(new PulseLengthStatAnalyzerResults(this, &mSettings));
SetAnalyzerResults(mResults.get());
mResults->AddChannelBubblesWillAppearOn(mSettings.mInputChannel);
}
void PulseLengthStatAnalyzer::WorkerThread()
{
mChannelData = GetAnalyzerChannelData(mSettings.mInputChannel);
U32 frames_since_commit = 0;
const U32 kCommitBatch = 256;
for (;;)
{
CheckIfThreadShouldExit();
const U64 segment_start = mChannelData->GetSampleNumber();
const BitState level = mChannelData->GetBitState();
mChannelData->AdvanceToNextEdge();
const U64 edge_sample = mChannelData->GetSampleNumber();
if (edge_sample == segment_start)
break;
const U64 duration_samples = edge_sample - segment_start;
const U64 end_inclusive = edge_sample > segment_start ? edge_sample - 1 : segment_start;
Frame frame;
frame.mData1 = duration_samples;
frame.mFlags = (level == BIT_HIGH) ? 1 : 0;
frame.mStartingSampleInclusive = static_cast<S64>(segment_start);
frame.mEndingSampleInclusive = static_cast<S64>(end_inclusive);
mResults->AddFrame(frame);
if (++frames_since_commit >= kCommitBatch)
{
mResults->CommitResults();
frames_since_commit = 0;
}
ReportProgress(edge_sample);
}
if (frames_since_commit != 0)
mResults->CommitResults();
}
bool PulseLengthStatAnalyzer::NeedsRerun()
{
return false;
}
U32 PulseLengthStatAnalyzer::GenerateSimulationData(U64 minimum_sample_index, U32 device_sample_rate,
SimulationChannelDescriptor** simulation_channels)
{
if (mSimulationInitilized == false)
{
mSimulationDataGenerator.Initialize(GetSimulationSampleRate(), &mSettings);
mSimulationInitilized = true;
}
return mSimulationDataGenerator.GenerateSimulationData(minimum_sample_index, device_sample_rate,
simulation_channels);
}
U32 PulseLengthStatAnalyzer::GetMinimumSampleRateHz()
{
return 200000;
}
const char* PulseLengthStatAnalyzer::GetAnalyzerName() const
{
return "Pulse Length Stat";
}
const char* GetAnalyzerName()
{
return "Pulse Length Stat";
}
Analyzer* CreateAnalyzer()
{
return new PulseLengthStatAnalyzer();
}
void DestroyAnalyzer(Analyzer* analyzer)
{
delete analyzer;
}

View File

@ -1,39 +0,0 @@
#ifndef PULSELENGTHSTAT_ANALYZER_H
#define PULSELENGTHSTAT_ANALYZER_H
#include <Analyzer.h>
#include "PulseLengthStatAnalyzerSettings.h"
#include "PulseLengthStatAnalyzerResults.h"
#include "PulseLengthStatSimulationDataGenerator.h"
#include <memory>
class ANALYZER_EXPORT PulseLengthStatAnalyzer : public Analyzer2
{
public:
PulseLengthStatAnalyzer();
virtual ~PulseLengthStatAnalyzer();
virtual void SetupResults();
virtual void WorkerThread();
virtual U32 GenerateSimulationData(U64 newest_sample_requested, U32 sample_rate,
SimulationChannelDescriptor** simulation_channels);
virtual U32 GetMinimumSampleRateHz();
virtual const char* GetAnalyzerName() const;
virtual bool NeedsRerun();
protected:
PulseLengthStatAnalyzerSettings mSettings;
std::unique_ptr<PulseLengthStatAnalyzerResults> mResults;
AnalyzerChannelData* mChannelData;
PulseLengthStatSimulationDataGenerator mSimulationDataGenerator;
bool mSimulationInitilized;
};
extern "C" ANALYZER_EXPORT const char* __cdecl GetAnalyzerName();
extern "C" ANALYZER_EXPORT Analyzer* __cdecl CreateAnalyzer();
extern "C" ANALYZER_EXPORT void __cdecl DestroyAnalyzer(Analyzer* analyzer);
#endif

View File

@ -1,107 +0,0 @@
#include "PulseLengthStatAnalyzerResults.h"
#include <AnalyzerHelpers.h>
#include "PulseLengthStatAnalyzer.h"
#include "PulseLengthStatAnalyzerSettings.h"
#include <cstdio>
#include <fstream>
PulseLengthStatAnalyzerResults::PulseLengthStatAnalyzerResults(PulseLengthStatAnalyzer* analyzer,
PulseLengthStatAnalyzerSettings* settings)
: AnalyzerResults(),
mSettings(settings),
mAnalyzer(analyzer)
{
}
PulseLengthStatAnalyzerResults::~PulseLengthStatAnalyzerResults()
{
}
static void FormatDurationUs(U64 duration_samples, U32 sample_rate_hz, char* out, size_t out_sz)
{
if (sample_rate_hz == 0)
{
snprintf(out, out_sz, "? us");
return;
}
const double us = double(duration_samples) * 1e6 / double(sample_rate_hz);
snprintf(out, out_sz, "%.2f us", us);
}
void PulseLengthStatAnalyzerResults::GenerateBubbleText(U64 frame_index, Channel& channel, DisplayBase display_base)
{
(void)display_base;
ClearResultStrings();
Frame frame = GetFrame(frame_index);
const U32 fs = mAnalyzer->GetSampleRate();
char dur[64];
FormatDurationUs(frame.mData1, fs, dur, sizeof dur);
const char* lev = (frame.mFlags != 0) ? "HIGH" : "LOW";
char line[160];
snprintf(line, sizeof line, "%s %s", lev, dur);
AddResultString(line);
}
void PulseLengthStatAnalyzerResults::GenerateExportFile(const char* file, DisplayBase display_base, U32 export_type_user_id)
{
(void)export_type_user_id;
(void)display_base;
std::ofstream file_stream(file, std::ios::out);
const U64 trigger_sample = mAnalyzer->GetTriggerSample();
const U32 sample_rate = mAnalyzer->GetSampleRate();
file_stream << "Time [s],Level,Duration_samples,Duration_us" << std::endl;
const U64 num_frames = GetNumFrames();
for (U32 i = 0; i < num_frames; i++)
{
Frame frame = GetFrame(i);
char time_str[128];
AnalyzerHelpers::GetTimeString(frame.mStartingSampleInclusive, trigger_sample, sample_rate, time_str, 128);
char dur_us[64];
FormatDurationUs(frame.mData1, sample_rate, dur_us, sizeof dur_us);
file_stream << time_str << "," << ((frame.mFlags != 0) ? "HIGH" : "LOW") << "," << frame.mData1 << ","
<< dur_us << std::endl;
if (UpdateExportProgressAndCheckForCancel(i, num_frames) == true)
{
file_stream.close();
return;
}
}
file_stream.close();
}
void PulseLengthStatAnalyzerResults::GenerateFrameTabularText(U64 frame_index, DisplayBase display_base)
{
#ifdef SUPPORTS_PROTOCOL_SEARCH
(void)display_base;
Frame frame = GetFrame(frame_index);
ClearTabularText();
const U32 fs = mAnalyzer->GetSampleRate();
char dur[64];
FormatDurationUs(frame.mData1, fs, dur, sizeof dur);
AddTabularText((frame.mFlags != 0) ? "H" : "L");
AddTabularText(dur);
#endif
}
void PulseLengthStatAnalyzerResults::GeneratePacketTabularText(U64 packet_id, DisplayBase display_base)
{
(void)packet_id;
(void)display_base;
}
void PulseLengthStatAnalyzerResults::GenerateTransactionTabularText(U64 transaction_id, DisplayBase display_base)
{
(void)transaction_id;
(void)display_base;
}

View File

@ -1,27 +0,0 @@
#ifndef PULSELENGTHSTAT_ANALYZER_RESULTS
#define PULSELENGTHSTAT_ANALYZER_RESULTS
#include <AnalyzerResults.h>
class PulseLengthStatAnalyzer;
class PulseLengthStatAnalyzerSettings;
class PulseLengthStatAnalyzerResults : public AnalyzerResults
{
public:
PulseLengthStatAnalyzerResults(PulseLengthStatAnalyzer* analyzer, PulseLengthStatAnalyzerSettings* settings);
virtual ~PulseLengthStatAnalyzerResults();
virtual void GenerateBubbleText(U64 frame_index, Channel& channel, DisplayBase display_base);
virtual void GenerateExportFile(const char* file, DisplayBase display_base, U32 export_type_user_id);
virtual void GenerateFrameTabularText(U64 frame_index, DisplayBase display_base);
virtual void GeneratePacketTabularText(U64 packet_id, DisplayBase display_base);
virtual void GenerateTransactionTabularText(U64 transaction_id, DisplayBase display_base);
protected:
PulseLengthStatAnalyzerSettings* mSettings;
PulseLengthStatAnalyzer* mAnalyzer;
};
#endif

View File

@ -1,62 +0,0 @@
#include "PulseLengthStatAnalyzerSettings.h"
#include <AnalyzerHelpers.h>
PulseLengthStatAnalyzerSettings::PulseLengthStatAnalyzerSettings()
: mInputChannel(UNDEFINED_CHANNEL),
mInputChannelInterface()
{
mInputChannelInterface.SetTitleAndTooltip(
"Input",
"Digital channel: one frame per stable level between edges (duration in samples / us).");
mInputChannelInterface.SetChannel(mInputChannel);
AddInterface(&mInputChannelInterface);
AddExportOption(0, "Export as text/csv file");
AddExportExtension(0, "text", "txt");
AddExportExtension(0, "csv", "csv");
ClearChannels();
AddChannel(mInputChannel, "Input", false);
}
PulseLengthStatAnalyzerSettings::~PulseLengthStatAnalyzerSettings()
{
}
bool PulseLengthStatAnalyzerSettings::SetSettingsFromInterfaces()
{
mInputChannel = mInputChannelInterface.GetChannel();
ClearChannels();
AddChannel(mInputChannel, "Pulse Length Stat", true);
return true;
}
void PulseLengthStatAnalyzerSettings::UpdateInterfacesFromSettings()
{
mInputChannelInterface.SetChannel(mInputChannel);
}
void PulseLengthStatAnalyzerSettings::LoadSettings(const char* settings)
{
SimpleArchive text_archive;
text_archive.SetString(settings);
text_archive >> mInputChannel;
ClearChannels();
AddChannel(mInputChannel, "Pulse Length Stat", true);
UpdateInterfacesFromSettings();
}
const char* PulseLengthStatAnalyzerSettings::SaveSettings()
{
SimpleArchive text_archive;
text_archive << mInputChannel;
return SetReturnString(text_archive.GetString());
}

View File

@ -1,24 +0,0 @@
#ifndef PULSELENGTHSTAT_ANALYZER_SETTINGS
#define PULSELENGTHSTAT_ANALYZER_SETTINGS
#include <AnalyzerSettings.h>
#include <AnalyzerTypes.h>
class PulseLengthStatAnalyzerSettings : public AnalyzerSettings
{
public:
PulseLengthStatAnalyzerSettings();
virtual ~PulseLengthStatAnalyzerSettings();
virtual bool SetSettingsFromInterfaces();
void UpdateInterfacesFromSettings();
virtual void LoadSettings(const char* settings);
virtual const char* SaveSettings();
Channel mInputChannel;
protected:
AnalyzerSettingInterfaceChannel mInputChannelInterface;
};
#endif

View File

@ -1,65 +0,0 @@
#include "PulseLengthStatSimulationDataGenerator.h"
#include "PulseLengthStatAnalyzerSettings.h"
#include <AnalyzerHelpers.h>
PulseLengthStatSimulationDataGenerator::PulseLengthStatSimulationDataGenerator()
{
}
PulseLengthStatSimulationDataGenerator::~PulseLengthStatSimulationDataGenerator()
{
}
void PulseLengthStatSimulationDataGenerator::Initialize(U32 simulation_sample_rate, PulseLengthStatAnalyzerSettings* settings)
{
mSimulationSampleRateHz = simulation_sample_rate;
mSettings = settings;
mSimChannel.SetChannel(mSettings->mInputChannel);
mSimChannel.SetSampleRate(simulation_sample_rate);
mSimChannel.SetInitialBitState(BIT_HIGH);
}
void PulseLengthStatSimulationDataGenerator::EmitIdle(U32 samples)
{
mSimChannel.Advance(samples);
}
void PulseLengthStatSimulationDataGenerator::EmitLow(U32 samples)
{
mSimChannel.TransitionIfNeeded(BIT_LOW);
mSimChannel.Advance(samples);
}
void PulseLengthStatSimulationDataGenerator::EmitHigh(U32 samples)
{
mSimChannel.TransitionIfNeeded(BIT_HIGH);
mSimChannel.Advance(samples);
}
U32 PulseLengthStatSimulationDataGenerator::GenerateSimulationData(U64 largest_sample_requested, U32 sample_rate,
SimulationChannelDescriptor** simulation_channel)
{
const U64 adjusted_largest_sample_requested =
AnalyzerHelpers::AdjustSimulationTargetSample(largest_sample_requested, sample_rate, mSimulationSampleRateHz);
while (mSimChannel.GetCurrentSampleNumber() < adjusted_largest_sample_requested)
{
const U32 us_to_samples = mSimulationSampleRateHz / 1000000;
if (us_to_samples == 0)
break;
EmitIdle(500 * us_to_samples);
EmitLow(4500 * us_to_samples);
EmitHigh(4500 * us_to_samples);
EmitLow(4500 * us_to_samples);
EmitHigh(4500 * us_to_samples);
EmitLow(560 * us_to_samples);
EmitHigh(560 * us_to_samples);
EmitLow(560 * us_to_samples);
EmitHigh(20000 * us_to_samples);
}
*simulation_channel = &mSimChannel;
return 1;
}

View File

@ -1,27 +0,0 @@
#ifndef PULSELENGTHSTAT_SIMULATION_DATA_GENERATOR
#define PULSELENGTHSTAT_SIMULATION_DATA_GENERATOR
#include <SimulationChannelDescriptor.h>
class PulseLengthStatAnalyzerSettings;
class PulseLengthStatSimulationDataGenerator
{
public:
PulseLengthStatSimulationDataGenerator();
~PulseLengthStatSimulationDataGenerator();
void Initialize(U32 simulation_sample_rate, PulseLengthStatAnalyzerSettings* settings);
U32 GenerateSimulationData(U64 newest_sample_requested, U32 sample_rate, SimulationChannelDescriptor** simulation_channel);
protected:
PulseLengthStatAnalyzerSettings* mSettings;
U32 mSimulationSampleRateHz;
SimulationChannelDescriptor mSimChannel;
void EmitIdle(U32 samples);
void EmitLow(U32 samples);
void EmitHigh(U32 samples);
};
#endif

View File

@ -1,5 +1,67 @@
#include "IR_Decoder.h"
#if defined(ARDUINO_ARCH_STM32) && !defined(HAL_EXTI_MODULE_DISABLED)
#include "Arduino.h"
/* NVIC_SetPriority — CMSIS, как в IR_Encoder::begin и Car.ino (без HAL-заголовка yyxx). */
/** NVIC для линии EXTI пина (как в Arduino STM32 SrcWrapper interrupt.cpp). */
static IRQn_Type ir_decoder_exti_irqn_for_pin(uint8_t arduino_pin)
{
#if defined(STM32C0xx) || defined(STM32F0xx) || defined(STM32G0xx) || defined(STM32L0xx)
(void)arduino_pin;
return (IRQn_Type)(-1);
#else
const PinName p = digitalPinToPinName(arduino_pin);
if (p == NC) {
return (IRQn_Type)(-1);
}
const uint16_t pinmask = STM_GPIO_PIN(p);
uint8_t id = 0U;
uint16_t pm = pinmask;
while (pm != 0x0001U) {
pm = (uint16_t)(pm >> 1U);
id++;
}
#if defined(STM32H5xx) || defined(STM32MP1xx) || defined(STM32L5xx) || defined(STM32U5xx) || defined(STM32WBAxx)
static const IRQn_Type exti_irqnb[16] = {
EXTI0_IRQn, EXTI1_IRQn, EXTI2_IRQn, EXTI3_IRQn, EXTI4_IRQn, EXTI5_IRQn, EXTI6_IRQn,
EXTI7_IRQn, EXTI8_IRQn, EXTI9_IRQn, EXTI10_IRQn, EXTI11_IRQn,
EXTI12_IRQn, EXTI13_IRQn, EXTI14_IRQn, EXTI15_IRQn};
#else
static const IRQn_Type exti_irqnb[16] = {
EXTI0_IRQn, EXTI1_IRQn, EXTI2_IRQn, EXTI3_IRQn, EXTI4_IRQn,
EXTI9_5_IRQn, EXTI9_5_IRQn, EXTI9_5_IRQn, EXTI9_5_IRQn, EXTI9_5_IRQn,
EXTI15_10_IRQn, EXTI15_10_IRQn, EXTI15_10_IRQn, EXTI15_10_IRQn,
EXTI15_10_IRQn, EXTI15_10_IRQn};
#endif
if (id < 16U) {
return exti_irqnb[id];
}
return (IRQn_Type)(-1);
#endif
}
static void ir_decoder_apply_rx_exti_nvic(uint8_t arduino_pin, uint32_t preempt)
{
const IRQn_Type irqn = ir_decoder_exti_irqn_for_pin(arduino_pin);
if ((int)irqn < 0) {
return;
}
#if !defined(STM32C0xx) && !defined(STM32F0xx) && !defined(STM32G0xx) && !defined(STM32L0xx)
NVIC_SetPriority(irqn, preempt);
#endif
}
void IR_Decoder::setReceiveExtiPreemptPriority(uint32_t preempt)
{
rxExtiPreemptConfigured_ = true;
rxExtiPreemptValue_ = preempt;
if (extiEnabled_) {
ir_decoder_apply_rx_exti_nvic(pin, preempt);
}
}
#endif /* ARDUINO_ARCH_STM32 && !HAL_EXTI_MODULE_DISABLED */
std::list<IR_Decoder *> &IR_Decoder::get_dec_list() // определение функции
{
static std::list<IR_Decoder *> dec_list; // статическая локальная переменная
@ -7,11 +69,11 @@ std::list<IR_Decoder *> &IR_Decoder::get_dec_list() // определение ф
}
// IR_Decoder::IR_Decoder() {};
IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair, bool autoHandle)
IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair, bool enableOnConstruct)
: IR_DecoderRaw(pin, addr, encPair)
{
get_dec_list().push_back(this);
if(autoHandle){
if (enableOnConstruct) {
enable();
}
};
@ -25,10 +87,17 @@ void IR_Decoder::enable()
}
pinMode(pin, INPUT_PULLUP);
attachInterrupt(pin, (*this)(), CHANGE);
extiEnabled_ = true;
#if defined(ARDUINO_ARCH_STM32) && !defined(HAL_EXTI_MODULE_DISABLED)
if (rxExtiPreemptConfigured_) {
ir_decoder_apply_rx_exti_nvic(pin, rxExtiPreemptValue_);
}
#endif
}
void IR_Decoder::disable()
{
extiEnabled_ = false;
detachInterrupt(pin);
pinMode(pin, INPUT);
auto &dec_list = get_dec_list();
@ -64,9 +133,6 @@ void IR_Decoder::_tick()
if (availableRaw())
{
#ifdef IRDEBUG_INFO
Serial.println("PARSING RAW DATA");
#endif
isWaitingAcceptSend = false;
switch (packInfo.buffer[0] >> 5 & IR_MASK_MSG_TYPE)
{

View File

@ -17,6 +17,10 @@ private:
uint16_t acceptDelay = IR_ResponseDelay;
uint8_t acceptCustomByte;
bool extiEnabled_ = false;
bool rxExtiPreemptConfigured_ = false;
uint32_t rxExtiPreemptValue_ = 0;
public:
PacketTypes::Data gotData;
PacketTypes::DataBack gotBackData;
@ -25,19 +29,38 @@ public:
PacketTypes::BasePack gotRaw;
// IR_Decoder();
IR_Decoder(const uint8_t pin, uint16_t addr = 0, IR_Encoder *encPair = nullptr, bool autoHandle = true);
/** @param enableOnConstruct true — вызвать enable() из конструктора; false — отложенный enable() (NVIC и т.д.), tick — tickThis() / tick(). */
IR_Decoder(const uint8_t pin, uint16_t addr = 0, IR_Encoder *encPair = nullptr, bool enableOnConstruct = true);
std::function<void()> operator()();
/**
* Arduino STM32: после attachInterrupt ядро выставляет свой приоритет EXTI.
* Если вызывали setReceiveExtiPreemptPriority(), здесь он применяется поверх (обычно нужен выше срочности, чем DMA ИК-TX).
* На других платформах поведение без изменений.
*/
void enable();
void disable();
#if defined(ARDUINO_ARCH_STM32) && !defined(HAL_EXTI_MODULE_DISABLED)
/**
* Задать preempt-приоритет NVIC для EXTI линии этого пина (тот же смысл, что второй аргумент CMSIS NVIC_SetPriority).
* Вызывайте до или после enable(); при активном приёме применяется сразу.
* При использовании DMA на передачу ИК preempt приёма должен быть меньше, чем у DMA TX (выше срочность прерывания).
*/
void setReceiveExtiPreemptPriority(uint32_t preempt);
#endif
bool isReceive(uint8_t type);
~IR_Decoder();
/** Обойти все экземпляры из внутреннего списка и вызвать tick у каждого. */
static void tick();
/** Tick только этого декодера (без обхода списка). Не комбинируйте с static tick() для того же экземпляра. */
void tickThis() { _tick(); }
inline void setAcceptDelay(uint16_t acceptDelay)
{
this->acceptDelay = acceptDelay;

View File

@ -1,5 +1,7 @@
#include "IR_DecoderRaw.h"
#include "IR_Encoder.h"
#include <cstdio>
#include <cstring>
IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair) : encoder(encPair)
{
@ -47,29 +49,11 @@ volatile uint32_t time_;
void IR_DecoderRaw::isr()
{
// Serial.print("ISR\n");
if(isPairSending){
return;
}
noInterrupts();
// time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1;
time_ = micros();
interrupts();
if (time_ < oldTime)
{
#ifdef IRDEBUG
Serial.print("\n");
Serial.print("count: ");
Serial.println(wrongCounter++);
Serial.print("time: ");
Serial.println(time_);
Serial.print("oldTime: ");
Serial.println(oldTime);
Serial.print("sub: ");
Serial.println(max((uint32_t)time_, oldTime) - min((uint32_t)time_, oldTime));
#endif
time_ += 1000;
}
oldTime = time_;
@ -78,6 +62,16 @@ void IR_DecoderRaw::isr()
edge.dir = port->IDR & mask;
edge.time = time_;
#if defined(IR_EDGE_TRACE)
edgeTracePush(edge.time, edge.dir ? 1u : 0u,
isPairSending ? (uint8_t)IR_EDGE_TRACE_F_SKIP_DECODE : 0u);
#endif
if (isPairSending)
{
return;
}
subBuffer.push(edge);
}
@ -85,9 +79,8 @@ void IR_DecoderRaw::isr()
void IR_DecoderRaw::firstRX()
{
#ifdef IRDEBUG_INFO
Serial.print("\nRX>");
#if defined(IRDEBUG_SERIAL_PACK)
packTraceResetFrame();
#endif
errors.reset();
@ -114,7 +107,9 @@ void IR_DecoderRaw::listenStart()
{
if (isReciveRaw && ((micros() - prevRise) > IR_timeout * 2))
{
// Serial.print("\nlis>");
#if defined(IRDEBUG_SERIAL_PACK)
packTraceOnTimeoutOrAbort(true);
#endif
isReciveRaw = false;
firstRX();
}
@ -128,6 +123,9 @@ inline void IR_DecoderRaw::checkTimeout()
if (micros() - lastEdgeTime > IR_timeout * 2U)
{
#if defined(IRDEBUG_SERIAL_PACK)
packTraceOnTimeoutOrAbort(false);
#endif
isRecive = false; // приём завершён
msgTypeReceive = 0;
// firstRX(); // подготовка к новому пакету
@ -153,6 +151,9 @@ void IR_DecoderRaw::tick()
isSubBufferOverflow = false;
checkTimeout(); // <--- новое место проверки
interrupts();
#if defined(IR_EDGE_TRACE)
while (edgeTraceFlushChunk(Serial, 48) > 0) {}
#endif
return;
} // Если данных нет - ничего не делаем
currentFront = *currentFrontPtr;
@ -244,6 +245,10 @@ void IR_DecoderRaw::tick()
isRecive = true;
isReciveRaw = true;
isWrongPack = false;
#if defined(IRDEBUG_SERIAL_PACK)
packTraceResetFrame();
packTraceOpen = true;
#endif
}
//-------------------------------------------------------------------------------------------------------
@ -251,8 +256,8 @@ void IR_DecoderRaw::tick()
if (preambFrontCounter)
{ // в преамбуле
#ifdef IRDEBUG
Serial.print("risePeriod: ");
Serial.println(risePeriod);
// Serial.print("risePeriod: ");
// Serial.println(risePeriod);
#endif
if (currentFront.dir && risePeriod < IR_timeout)
{ // __/``` ↑ и мы в внутри пакета
@ -312,21 +317,21 @@ void IR_DecoderRaw::tick()
lowCount = 0;
allCount = 0;
bool invertErr = false;
#ifdef IRDEBUG
Serial.print("\n");
// #ifdef IRDEBUG
// Serial.print("\n");
Serial.print("wrCounter: ");
Serial.println(wrCounter++);
// Serial.print("wrCounter: ");
// Serial.println(wrCounter++);
Serial.print("risePeriod: ");
Serial.println(risePeriod);
// Serial.print("risePeriod: ");
// Serial.println(risePeriod);
Serial.print("highTime: ");
Serial.println(highTime);
// Serial.print("highTime: ");
// Serial.println(highTime);
Serial.print("lowTime: ");
Serial.println(lowTime);
#endif
// Serial.print("lowTime: ");
// Serial.println(lowTime);
// #endif
if (aroundRise(risePeriod))
{ // тактирование есть, сигнал хороший - без ошибок(?)
@ -420,7 +425,7 @@ void IR_DecoderRaw::tick()
if (i == lowCount - 1 && invertErr)
{
invertErr = false;
writeToBuffer(HIGH);
writeToBuffer(HIGH, true);
#ifdef IRDEBUG
errPulse(wrHigh, 1);
#endif
@ -439,7 +444,7 @@ void IR_DecoderRaw::tick()
if (i == highCount - 1 && invertErr)
{
invertErr = false;
writeToBuffer(LOW);
writeToBuffer(LOW, true);
#ifdef IRDEBUG
errPulse(wrLow, 1);
#endif
@ -460,17 +465,23 @@ void IR_DecoderRaw::tick()
////////////////////////////////////////////////////////////////////////////////////////////////////////////
END:;
#if defined(IR_EDGE_TRACE)
while (edgeTraceFlushChunk(Serial, 48) > 0) {}
#endif
}
void IR_DecoderRaw::writeToBuffer(bool bit)
void IR_DecoderRaw::writeToBuffer(bool bit, bool packTraceInvertFix)
{
#if !defined(IRDEBUG_SERIAL_PACK)
(void)packTraceInvertFix;
#endif
if (i_dataBuffer > dataByteSizeMax * 8)
{ // проверка переполнения
// TODO: Буффер переполнен!
#ifdef IRDEBUG_INFO
Serial.println("OverBuf");
#endif
isBufferOverflow = true;
#if defined(IRDEBUG_SERIAL_PACK)
if (packTraceOpen)
packTraceEmitErrorFlash(F("ERROR: buffer overflow"));
#endif
}
if (isBufferOverflow || isPreamb || isWrongPack)
{
@ -487,112 +498,98 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
isData = !isData;
i_syncBit = 0; // сброс счетчика битов синхронизации
err_syncBit = 0; // сброс счетчика ошибок синхронизации
#ifdef IRDEBUG_INFO
Serial.print(" ");
#endif
}
if (isData)
{ // Запись битов в dataBuffer
#ifdef IRDEBUG_INFO
Serial.print(bit);
#endif
// if (i_dataBuffer % 8 == 7) {
// // Serial.print("+");
// }
dataBuffer[(i_dataBuffer / 8)] |= bit << (7 - i_dataBuffer % 8); // Запись в буффер
i_dataBuffer++;
bufBitPos++;
#if defined(IRDEBUG_SERIAL_PACK)
if (packTraceInvertFix)
{
packTracePushChar('`');
packTracePushChar(bit ? '1' : '0');
packTracePushChar('`');
}
else
packTracePushBit(bit);
#endif
}
else
{
//********************************* Проверка контрольных sync битов*******************************//
//********************************* Проверка контрольных sync битов *******************************//
////////////////////// Исправление лишнего нуля ///////////////////////
if (i_syncBit == 0)
{ // Первый бит синхронизации
// Serial.print("~");
if (bit != (dataBuffer[((i_dataBuffer - 1) / 8)] >> (7 - (i_dataBuffer - 1) % 8) & 1))
{
bufBitPos++;
i_syncBit++;
#if defined(IRDEBUG_SERIAL_PACK)
packTracePushBit(bit);
#endif
}
else
{
i_syncBit = 0;
errors.other++;
// Serial.print("E");
err_syncBit++;
// Serial.print("bit: "); Serial.println(bit);
// Serial.print("dataBuffer: "); Serial.println(dataBuffer[((i_dataBuffer - 1) / 8)] & 1 << (7 - ((i_dataBuffer - 1) & ~(~0 << 3))));
const bool fatalSync = (err_syncBit >= syncBits);
if (fatalSync)
{
#if defined(IRDEBUG_SERIAL_PACK) && defined(IRDEBUG_SERIAL_SOFT_REJECT)
if (packTraceSoftReject())
{
packTraceHadWrongSync = true;
packTraceForceEndSyncPhase();
err_syncBit = 0;
i_syncBit = 0;
isWrongPack = false;
}
else
#endif
{
isWrongPack = true;
#if defined(IRDEBUG_SERIAL_PACK)
packTraceEmitErrorFlash(F("ERROR: Wrong sync bit"));
#endif
}
}
}
}
else
{ // Последующие биты синхронизации
// Serial.print("`");
bufBitPos++;
i_syncBit++;
}
////////////////////// Проверка наличия битов синхранизации //////////////////////
if (isWrongPack = (err_syncBit >= syncBits))
{
#ifdef IRDEBUG_INFO
Serial.print("****************");
#if defined(IRDEBUG_SERIAL_PACK)
packTracePushBit(bit);
#endif
};
}
isWrongPack = (err_syncBit >= syncBits);
} //**************************************************************************************************//
// Serial.print(bit);
#ifdef IRDEBUG
bit ? infoPulse(writeOp, 2) : infoPulse(writeOp, 1);
#endif
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
#ifdef IRDEBUG_INFO
if (isData)
{
if (i_dataBuffer == ((msgBytes)*bitPerByte))
{
Serial.print(" -> ");
Serial.print(dataBuffer[0] & IR_MASK_MSG_INFO);
Serial.print(" ->");
}
if (i_dataBuffer == ((msgBytes + addrBytes) * bitPerByte))
{
Serial.print(" |");
}
if (i_dataBuffer == ((msgBytes + addrBytes + addrBytes) * bitPerByte))
{
Serial.print(" ->");
}
if (i_dataBuffer == (((dataBuffer[0] & IR_MASK_MSG_INFO) - 2) * bitPerByte))
{
Serial.print(" <-");
}
}
#endif
if (!isAvailable && isData && !isWrongPack)
{
if (i_dataBuffer == 8 * msgBytes)
{ // Ппервый байт
packSize = dataBuffer[0] & IR_MASK_MSG_INFO;
#ifdef IRDEBUG_INFO
Serial.print(" [");
Serial.print(packSize);
Serial.print("] ");
#endif
}
// Тип приёма (для isReceive): выставляем сразу после первого байта, ДО проверки «Конец».
// Иначе при packSize==1 один и тот же шаг i_dataBuffer==8 одновременно «закрывает» кадр (msgTypeReceive=0)
// и снова выставляет msgTypeReceive ниже — флаг залипает, пока не придёт ошибка/другой кадр.
if (packSize && (i_dataBuffer == 8))
{
msgTypeReceive = (dataBuffer[0] >> 5) | 0b11111000;
}
if (packSize && (i_dataBuffer == packSize * bitPerByte))
{ // Конец
#ifdef IRDEBUG_INFO
Serial.print(" END DATA " + crcCheck(packSize - crcBytes, crcValue) ? "OK " : "ERR ");
#endif
packInfo.buffer = dataBuffer;
packInfo.crc = crcValue;
packInfo.err = errors;
@ -605,6 +602,10 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
isAvailable = crcCheck(packSize - crcBytes, crcValue);
#ifdef BRUTEFORCE_CHECK
{
uint16_t packTraceBfByte = 0;
uint8_t packTraceBfBit = 0;
bool packTraceBfMark = false;
if (!isAvailable) // Исправление первого бита // Очень большая затычка...
for (size_t i = 0; i < min(uint16_t(packSize - crcBytes * 2U), uint16_t(dataByteSizeMax)); ++i)
{
@ -613,14 +614,15 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
// инвертируем бит
dataBuffer[i] ^= 1 << j;
isAvailable = crcCheck(min(uint16_t(packSize - crcBytes), uint16_t(dataByteSizeMax - 1U)), crcValue);
isAvailable =
crcCheck(min(uint16_t(packSize - crcBytes), uint16_t(dataByteSizeMax - 1U)), crcValue);
// обратно инвертируем бит в исходное состояние
if (isAvailable)
{
#ifdef IRDEBUG_INFO
Serial.println("!!!INV!!!");
#endif
packTraceBfByte = static_cast<uint16_t>(i);
packTraceBfBit = static_cast<uint8_t>(j);
packTraceBfMark = true;
goto OUT_BRUTEFORCE;
}
else
@ -629,14 +631,24 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
}
}
}
OUT_BRUTEFORCE:;
OUT_BRUTEFORCE:
#if defined(IRDEBUG_SERIAL_PACK)
if (packTraceBfMark)
packTraceWrapDataBitInBackticks(packTraceBfByte, packTraceBfBit);
#endif
}
if (packSize && (i_dataBuffer == 8)) {
msgTypeReceive = (dataBuffer[0]>>5) | 0b11111000;
// SerialUSB.println(msgTypeReceive & IR_MASK_MSG_TYPE);
#endif
#if defined(IRDEBUG_SERIAL_PACK)
if (isAvailable)
packTraceEmitEndOk(static_cast<uint8_t>(packSize));
else
packTraceEmitEndBadCrc(static_cast<uint8_t>(packSize));
#endif
if (!isAvailable && packSize > 0 && packSize <= dataByteSizeMax) {
memcpy(rejectBuffer, dataBuffer, packSize);
rejectPackSize = static_cast<uint8_t>(packSize);
isRejectAvailable = true;
}
}
}
@ -651,9 +663,7 @@ bool IR_DecoderRaw::crcCheck(uint8_t len, crc_t &crc)
crc = (crc8(dataBuffer, 0, len, poly1) << 8) & ~((crc_t)0xFF);
crc |= crc8(dataBuffer, 0, len + 1, poly2) & (crc_t)0xFF;
if (
crc &&
dataBuffer[len] == (crc >> 8) & 0xFF &&
if (dataBuffer[len] == (crc >> 8) & 0xFF &&
dataBuffer[len + 1] == (crc & 0xFF))
{
crcOK = true;
@ -666,6 +676,14 @@ bool IR_DecoderRaw::crcCheck(uint8_t len, crc_t &crc)
return crcOK;
}
bool IR_DecoderRaw::availableReject()
{
if (!isRejectAvailable)
return false;
isRejectAvailable = false;
return true;
}
uint16_t IR_DecoderRaw::ceil_div(uint16_t val, uint16_t divider)
{
int ret = val / divider;
@ -674,6 +692,461 @@ uint16_t IR_DecoderRaw::ceil_div(uint16_t val, uint16_t divider)
return ret;
}
#if defined(IR_EDGE_TRACE)
void IR_DecoderRaw::edgeTracePush(uint32_t t_us, uint8_t level, uint8_t flags)
{
const uint16_t cap = static_cast<uint16_t>(IR_EDGE_TRACE_CAPACITY);
noInterrupts();
const uint16_t w = edgeTrace_w;
const uint16_t r = edgeTrace_r;
const uint16_t next = static_cast<uint16_t>((w + 1u) % cap);
if (next == r)
{
edgeTrace_overflow = true;
interrupts();
return;
}
edgeTrace_buf[w].t_us = t_us;
edgeTrace_buf[w].level = level ? 1u : 0u;
edgeTrace_buf[w].flags = flags;
edgeTrace_w = next;
interrupts();
}
void IR_DecoderRaw::edgeTraceClear()
{
noInterrupts();
edgeTrace_w = 0;
edgeTrace_r = 0;
edgeTrace_overflow = false;
interrupts();
}
uint16_t IR_DecoderRaw::edgeTracePendingCount() const
{
noInterrupts();
const uint16_t w = edgeTrace_w;
const uint16_t r = edgeTrace_r;
interrupts();
const uint16_t cap = static_cast<uint16_t>(IR_EDGE_TRACE_CAPACITY);
if (w >= r)
return static_cast<uint16_t>(w - r);
return static_cast<uint16_t>(cap - r + w);
}
uint16_t IR_DecoderRaw::edgeTraceFlushChunk(Print &out, uint16_t maxRec)
{
if (maxRec == 0)
maxRec = 48;
constexpr uint16_t kStackCap = 64;
if (maxRec > kStackCap)
maxRec = kStackCap;
const uint16_t cap = static_cast<uint16_t>(IR_EDGE_TRACE_CAPACITY);
noInterrupts();
const uint16_t w = edgeTrace_w;
const uint16_t r = edgeTrace_r;
uint16_t avail = (w >= r) ? static_cast<uint16_t>(w - r) : static_cast<uint16_t>(cap - r + w);
uint16_t toCopy = (avail > maxRec) ? maxRec : avail;
const bool truncated = (avail > toCopy);
if (toCopy == 0)
{
interrupts();
return 0;
}
uint8_t tmp[kStackCap * 6];
for (uint16_t i = 0; i < toCopy; ++i)
{
const uint16_t idx = static_cast<uint16_t>((r + i) % cap);
memcpy(tmp + i * 6u, &edgeTrace_buf[idx], 6u);
}
edgeTrace_r = static_cast<uint16_t>((r + toCopy) % cap);
const bool ovf = edgeTrace_overflow;
interrupts();
uint8_t meta = 0;
if (ovf)
meta |= 0x01u;
if (truncated)
meta |= 0x02u;
uint8_t line[3 + kStackCap * 6];
line[0] = meta;
line[1] = static_cast<uint8_t>(toCopy & 0xFFu);
line[2] = static_cast<uint8_t>((toCopy >> 8) & 0xFFu);
memcpy(line + 3, tmp, toCopy * 6u);
out.print(F("\n@IRF1v1:"));
static const char hd[] = "0123456789abcdef";
const uint16_t lineLen = static_cast<uint16_t>(3u + toCopy * 6u);
for (uint16_t i = 0; i < lineLen; ++i)
{
const uint8_t b = line[i];
out.write(hd[b >> 4]);
out.write(hd[b & 0x0Fu]);
}
out.write('\n');
return toCopy;
}
#endif // IR_EDGE_TRACE
#if defined(IRDEBUG_SERIAL_PACK)
struct IrPackTraceSeg
{
uint8_t isSync;
uint8_t nbits; // число логических бит (данные) или символов синхры
uint8_t nchars; // сырых символов в b (данные: 8…24 из‑за `0`/`1`)
char b[24];
};
namespace {
void ptPrintHexU8(uint8_t v)
{
static const char hd[] = "0123456789ABCDEF";
Serial.print(hd[v >> 4]);
Serial.print(hd[v & 0x0Fu]);
}
/** Тройной пробел перед началом блока: msg→from, from→to, to→data, data→CRC. */
static bool ptRawLeadTriple(uint8_t byteIndex, uint8_t framePs)
{
if (byteIndex == 1 || byteIndex == 3)
return true;
if (framePs > 7 && byteIndex == 5)
return true;
if (framePs >= 7 && byteIndex == static_cast<uint8_t>(framePs - 2))
return true;
return false;
}
/** В IR raw: только 0/1 из flex-сегмента (без `), takeBits логических бит после skipLogical. */
static void ptEmitRawFlexSliceSerial(const char *s, uint8_t nbytes, uint8_t skipLogical, uint8_t takeBits)
{
size_t i = 0;
uint8_t logical = 0;
uint8_t emitted = 0;
while (i < nbytes && emitted < takeBits)
{
if (s[i] == '`' && i + 2u < nbytes && (s[i + 1] == '0' || s[i + 1] == '1') && s[i + 2] == '`')
{
if (logical >= skipLogical)
{
Serial.print(s[i + 1]);
++emitted;
}
i += 3;
++logical;
}
else if (s[i] == '0' || s[i] == '1')
{
if (logical >= skipLogical)
{
Serial.print(s[i]);
++emitted;
}
++i;
++logical;
}
else
break;
}
}
static bool ptTryConsumeFlexDataBit(const char *buf, uint16_t len, uint16_t &pos, IrPackTraceSeg &d)
{
if (pos + 2 < len && buf[pos] == '`' && (buf[pos + 1] == '0' || buf[pos + 1] == '1') && buf[pos + 2] == '`')
{
if (d.nchars + 3u > sizeof(d.b))
return false;
d.b[d.nchars++] = '`';
d.b[d.nchars++] = buf[pos + 1];
d.b[d.nchars++] = '`';
pos = static_cast<uint16_t>(pos + 3u);
return true;
}
if (pos < len && (buf[pos] == '0' || buf[pos] == '1'))
{
if (d.nchars + 1u > sizeof(d.b))
return false;
d.b[d.nchars++] = buf[pos++];
return true;
}
return false;
}
} // namespace
void IR_DecoderRaw::packTraceResetFrame()
{
packTraceOpen = false;
packTraceHadWrongSync = false;
packTraceLen = 0;
packTraceBitBuf[0] = '\0';
}
void IR_DecoderRaw::packTracePushChar(char c)
{
if (packTraceLen + 1u < kPackTraceBufCap)
{
packTraceBitBuf[packTraceLen++] = c;
packTraceBitBuf[packTraceLen] = '\0';
}
}
void IR_DecoderRaw::packTracePushBit(bool bit) { packTracePushChar(bit ? '1' : '0'); }
void IR_DecoderRaw::packTraceWrapDataBitInBackticks(uint16_t byteIndex, uint8_t bitInByte)
{
const uint32_t target = uint32_t(byteIndex) * 8u + bitInByte;
uint32_t dbit = 0;
uint16_t pos = 0;
bool inData = true;
uint16_t len = packTraceLen;
if (len >= kPackTraceBufCap)
len = kPackTraceBufCap - 1u;
while (pos < len)
{
if (inData)
{
uint8_t bitLen = 0;
if (pos + 2 < len && packTraceBitBuf[pos] == '`' && packTraceBitBuf[pos + 2] == '`' &&
(packTraceBitBuf[pos + 1] == '0' || packTraceBitBuf[pos + 1] == '1'))
bitLen = 3;
else if (packTraceBitBuf[pos] == '0' || packTraceBitBuf[pos] == '1')
bitLen = 1;
else
return;
if (dbit == target)
{
if (bitLen == 3)
return;
if (packTraceLen + 2u >= kPackTraceBufCap)
return;
const uint8_t finalBit =
static_cast<uint8_t>((dataBuffer[byteIndex] >> (7u - bitInByte)) & 1u);
const char ch = finalBit ? '1' : '0';
memmove(packTraceBitBuf + pos + 2, packTraceBitBuf + pos, packTraceLen - pos);
packTraceBitBuf[pos] = '`';
packTraceBitBuf[pos + 1] = ch;
packTraceBitBuf[pos + 2] = '`';
packTraceLen += 2;
if (packTraceLen < kPackTraceBufCap)
packTraceBitBuf[packTraceLen] = '\0';
return;
}
++dbit;
pos = static_cast<uint16_t>(pos + bitLen);
if ((dbit % 8u) == 0u)
inData = false;
}
else
{
uint8_t sc = 0;
while (pos < len && sc < syncBits)
{
const char c = packTraceBitBuf[pos];
if (c == '0' || c == '1' || c == '?')
{
++pos;
++sc;
}
else
break;
}
inData = true;
}
}
}
bool IR_DecoderRaw::packTraceSoftReject() const
{
#if defined(IRDEBUG_SERIAL_SOFT_REJECT)
return true;
#else
return false;
#endif
}
void IR_DecoderRaw::packTraceForceEndSyncPhase()
{
for (uint8_t i = 0; i < syncBits; i++)
packTracePushChar('?');
const uint8_t cycLen = bitPerByte + syncBits;
const uint16_t cyc = uint16_t(bufBitPos / cycLen);
bufBitPos = uint16_t((cyc + 1u) * cycLen);
if (bufBitPos == nextControlBit)
{
nextControlBit += (isData ? syncBits : bitPerByte);
isData = !isData;
i_syncBit = 0;
err_syncBit = 0;
}
}
void IR_DecoderRaw::packTraceEmitHex(uint8_t byteCount) const
{
Serial.print(F("IR hex:"));
for (uint8_t i = 0; i < byteCount && i < dataByteSizeMax; i++)
{
Serial.print(' ');
ptPrintHexU8(dataBuffer[i]);
}
Serial.println();
}
void IR_DecoderRaw::packTraceEmitRawBitsLine(bool endWithNewline) const
{
Serial.print(F("IR raw: "));
uint16_t len = packTraceLen;
if (len >= kPackTraceBufCap)
len = kPackTraceBufCap - 1u;
const char *buf = packTraceBitBuf;
uint16_t pos = 0;
uint8_t byteIndex = 0;
bool firstSeg = true;
const uint8_t framePs =
(i_dataBuffer >= 8) ? static_cast<uint8_t>(dataBuffer[0] & IR_MASK_MSG_INFO) : 0;
while (pos < len)
{
IrPackTraceSeg d{};
d.isSync = 0;
while (pos < len && d.nbits < 8)
{
const uint16_t posBefore = pos;
if (!ptTryConsumeFlexDataBit(buf, len, pos, d))
break;
if (pos == posBefore)
break;
++d.nbits;
}
if (!d.nbits)
break;
if (!firstSeg)
{
if (ptRawLeadTriple(byteIndex, framePs))
Serial.print(F(" "));
else
Serial.print(' ');
}
firstSeg = false;
if (d.nbits < 8)
{
ptEmitRawFlexSliceSerial(d.b, d.nchars, 0, d.nbits);
break;
}
if (byteIndex == 0u)
{
ptEmitRawFlexSliceSerial(d.b, d.nchars, 0, 3);
Serial.print(' ');
ptEmitRawFlexSliceSerial(d.b, d.nchars, 3, 5);
}
else
ptEmitRawFlexSliceSerial(d.b, d.nchars, 0, 8);
++byteIndex;
if (pos >= len)
break;
IrPackTraceSeg s{};
s.isSync = 1;
while (pos < len && s.nbits < syncBits)
{
const char c = buf[pos];
if (c != '0' && c != '1' && c != '?')
break;
if (s.nchars >= sizeof(s.b))
break;
s.b[s.nchars++] = c;
++s.nbits;
++pos;
}
if (s.nbits)
{
Serial.print(' ');
for (uint8_t i = 0; i < s.nbits; ++i)
Serial.print(s.b[i]);
}
}
if (endWithNewline)
Serial.println();
}
void IR_DecoderRaw::packTraceEmitErrorFlash(const __FlashStringHelper *msg)
{
Serial.println();
packTraceEmitRawBitsLine(false);
Serial.print(F(" => "));
Serial.println(msg);
{
uint16_t nb = i_dataBuffer / 8u;
if (nb > dataByteSizeMax)
nb = dataByteSizeMax;
packTraceEmitHex(static_cast<uint8_t>(nb));
}
packTraceResetFrame();
}
void IR_DecoderRaw::packTraceEmitEndOk(uint8_t packSize)
{
Serial.println();
packTraceEmitRawBitsLine(false);
Serial.print(F(" => OK: "));
irPackTracePrintOkCommand(dataBuffer, packSize);
Serial.println();
packTraceEmitHex(packSize);
packTraceResetFrame();
}
void IR_DecoderRaw::packTraceEmitEndBadCrc(uint8_t packSize)
{
Serial.println();
packTraceEmitRawBitsLine(false);
Serial.println(F(" => ERROR: Wrong CRC"));
packTraceEmitHex(packSize);
packTraceResetFrame();
}
void IR_DecoderRaw::packTraceOnTimeoutOrAbort(bool fromListenStart)
{
(void)fromListenStart;
if (!packTraceOpen)
return;
const uint16_t expected = (i_dataBuffer >= 8) ? uint16_t(dataBuffer[0] & IR_MASK_MSG_INFO) : 0;
uint16_t gotBytes = i_dataBuffer / 8;
if (gotBytes > dataByteSizeMax)
gotBytes = dataByteSizeMax;
Serial.println();
packTraceEmitRawBitsLine(false);
Serial.print(F(" => ERROR: TIMEOUT, rx_data_size = "));
Serial.print(expected);
Serial.print(F(", but only "));
Serial.print(gotBytes);
Serial.println(F(" bytes received"));
packTraceEmitHex(static_cast<uint8_t>(gotBytes));
packTraceResetFrame();
}
__attribute__((weak)) void irPackTracePrintOkCommand(const uint8_t *buf, uint8_t packSize)
{
(void)buf;
(void)packSize;
}
#endif // IRDEBUG_SERIAL_PACK
// IRDEBUG FUNC
#ifdef IRDEBUG
inline void IR_DecoderRaw::errPulse(uint8_t pin, uint8_t count)

View File

@ -2,17 +2,19 @@
#include "IR_config.h"
#include "RingBuffer.h"
// #define IRDEBUG
class Print;
#define IRDEBUG
#ifdef IRDEBUG
#define wrHigh PA1 // Запись HIGH инициирована // green
#define wrLow PA0 // Запись LOW инициирована // blue
#define writeOp PA5 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
#define wrHigh 255 // Запись HIGH инициирована // green
#define wrLow 255 // Запись LOW инициирована // blue
#define writeOp 255 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
// Исправленные ошибки // purle
// 1 пульс: fix
#define errOut PA4
#define up PA3
#define down PA2
#define errOut 255
#define up 255
#define down 255
#endif
/////////////////////////////////////////////////////////////////////////////////////////////////
@ -51,8 +53,25 @@ public:
bool isSubOverflow();
volatile inline bool isReciving() { return isRecive; }; // Возвращает true, если происходит приём пакета
#if defined(IR_EDGE_TRACE)
void edgeTraceClear();
bool edgeTraceOverflow() const { return edgeTrace_overflow; }
uint16_t edgeTracePendingCount() const;
/** При непустом кольце: перевод строки + @IRF1v1: + hex; в tick() сброс на Serial автоматически. См. ref/IR_EDGE_TRACE_FORMAT.md */
uint16_t edgeTraceFlushChunk(Print &out, uint16_t maxRec = 48);
#endif
/// Кадр собран по длине из заголовка, но CRC не сошёлся — один раз можно прочитать копию сырых байтов.
bool availableReject();
uint8_t getRejectSize() const { return rejectPackSize; }
const uint8_t* getRejectBuffer() const { return rejectBuffer; }
//////////////////////////////////////////////////////////////////////////
private:
bool isRejectAvailable = false;
uint8_t rejectPackSize = 0;
uint8_t rejectBuffer[dataByteSizeMax]{};
ErrorsStruct errors;
bool isAvailable = false;
uint16_t packSize;
@ -83,6 +102,20 @@ private:
RingBuffer<FrontStorage, subBufferSize> subBuffer;
#if defined(IR_EDGE_TRACE)
struct IrEdgeTraceRec
{
uint32_t t_us;
uint8_t level;
uint8_t flags;
};
void edgeTracePush(uint32_t t_us, uint8_t level, uint8_t flags);
IrEdgeTraceRec edgeTrace_buf[IR_EDGE_TRACE_CAPACITY]{};
volatile uint16_t edgeTrace_w = 0;
volatile uint16_t edgeTrace_r = 0;
volatile bool edgeTrace_overflow = false;
#endif
////////////////////////////////////////////////////////////////////////
uint8_t dataBuffer[dataByteSizeMax]{0}; // Буффер данных
volatile uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
@ -121,8 +154,8 @@ bool isReciveRaw;
uint8_t err_syncBit; // Счётчик ошибок синхронизации
/// @brief Запиь бита в буффер, а так же проверка битов синхранизации и их фильтрация
/// @param Бит данных
void writeToBuffer(bool);
/// @param packTraceInvertFix если true — в IRDEBUG_SERIAL_PACK бит в трассе пишется как `0`/`1` (исправление по фронтам)
void writeToBuffer(bool bit, bool packTraceInvertFix = false);
////////////////////////////////////////////////////////////////////////
void firstRX(); /// @brief Установка и сброс начальных значений и флагов в готовность к приёму данных
@ -138,4 +171,30 @@ bool isReciveRaw;
inline void errPulse(uint8_t pin, uint8_t count);
inline void infoPulse(uint8_t pin, uint8_t count);
#endif
#if defined(IRDEBUG_SERIAL_PACK)
static constexpr uint16_t kPackTraceBufCap =
uint16_t(dataByteSizeMax) * (uint16_t(bitPerByte) + uint16_t(syncBits)) + 48u;
void packTraceResetFrame();
void packTracePushBit(bool bit);
void packTracePushChar(char c);
/** Помечает в packTraceBitBuf бит (после BRUTEFORCE_CHECK) обёрткой `0`/`1` по финальному значению в dataBuffer. */
void packTraceWrapDataBitInBackticks(uint16_t byteIndex, uint8_t bitInByte);
/** IR hex: все байты dataBuffer[0 .. byteCount-1] в hex. */
void packTraceEmitHex(uint8_t byteCount) const;
/** IR raw: биты и синхра; тройной пробел между блоками msg/from/to/data/CRC; первый байт 3+пробел+5. endWithNewline — перевод строки после сырой строки. */
void packTraceEmitRawBitsLine(bool endWithNewline = true) const;
void packTraceEmitErrorFlash(const __FlashStringHelper *msg);
void packTraceEmitEndOk(uint8_t packSize);
void packTraceEmitEndBadCrc(uint8_t packSize);
void packTraceOnTimeoutOrAbort(bool fromListenStart);
void packTraceForceEndSyncPhase();
bool packTraceSoftReject() const;
bool packTraceOpen = false;
bool packTraceHadWrongSync = false;
char packTraceBitBuf[kPackTraceBufCap]{};
uint16_t packTraceLen = 0;
#endif
};

View File

@ -463,7 +463,7 @@ IR_SendResult IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *d
uint8_t packSize = msgBytes + addrBytes + (isAdressed ? addrBytes : 0) + min(uint8_t(1), len) + crcBytes;
uint8_t msgType =
((isAdressed ? IR_MSG_BACK_TO : IR_MSG_BACK) << 5) | ((packSize) & (IR_MASK_MSG_INFO >> 1));
((isAdressed ? IR_MSG_BACK_TO : IR_MSG_BACK) << 5) | ((packSize) & IR_MASK_MSG_INFO);
// формирование массива
// msg_type

View File

@ -2,6 +2,32 @@
#include <Arduino.h>
#include <list>
// #define IRDEBUG_INFO
/** Число потоков DMA-TX задаётся шаблоном: IrDmaTxStm32<2>, см. IrDmaTxStm32.h и irproto::kDefaultDmaTxMaxStreams. */
namespace irproto {
constexpr size_t kDefaultDmaTxMaxStreams = 4U;
}
// Пошаговый разбор кадра на Serial (по умолчанию выключено). Пульсы IRDEBUG на пинах не меняют.
// #define IRDEBUG_SERIAL_PACK
// Не обрывать приём сразу при накопленной sync-ошибке — «дописывать» до таймаута (только вместе с IRDEBUG_SERIAL_PACK).
// #define IRDEBUG_SERIAL_SOFT_REJECT
// Журнал фронтов ИК в ISR; сброс строк @IRF1v1: в IR_DecoderRaw::tick(). См. ref/IR_EDGE_TRACE_FORMAT.md
// Расход RAM ≈ IR_EDGE_TRACE_CAPACITY * 6 байт на декодер. Выключить — закомментировать:
// #define IR_EDGE_TRACE
#if defined(IR_EDGE_TRACE)
#ifndef IR_EDGE_TRACE_CAPACITY
#define IR_EDGE_TRACE_CAPACITY 512u
#endif
/** Запись в edgeTrace: фронт не передан в decode (isPairSending). */
#define IR_EDGE_TRACE_F_SKIP_DECODE 0x01u
#endif
// Пример в скетче: void irPackTracePrintOkCommand(const uint8_t* b, uint8_t n) { Serial.print(F("CarCmd::...")); }
#if defined(IRDEBUG_SERIAL_PACK)
/** Слабая реализация в IR_DecoderRaw.cpp; в скетче определите свою для вывода вроде CarCmd::... */
void irPackTracePrintOkCommand(const uint8_t *buf, uint8_t packSize);
#endif
/*//////////////////////////////////////////////////////////////////////////////////////
Для работы в паре положить декодер в энкодер
@ -48,12 +74,13 @@
\____________________________________________________________________________________________________/    
msg type:
                                        //  __________
                                        // | 01234567 |
                                        //  ----------
                                        // | xxx..... | = тип сообщения
                                        // | ...xxxxx | = длина (максимум 31 бита) - не больше 24 байт на тело пакета
                                        //  ---------- */
                                //  __________
                                // | 01234567 |
                                //  ----------
                                // | xxx..... | = тип сообщения (биты 7..5)
                                // | ...xxxxx | = полная длина кадра в байтах (5 бит, 0..31, IR_MASK_MSG_INFO), не «31 бит» и не отдельный лимит «24 байта»
                                // Полезная нагрузка в data pack: до bytePerPack байт (см. #define bytePerPack).
                                //  ---------- */
#define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки
#define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение
#define IR_MSG_REQUEST 2U // | 010..... | = запрос
@ -81,12 +108,13 @@ msg type:
/`````````````````````` Задний сигнал машинки без адресации ``````````````````````\        
// Первый байт: (IR_MSG_BACK<<5) | (packSize & IR_MASK_MSG_INFO) — как у data pack (тип + длина 0..31).
                                                                                           
{``````````} [````````````````````````] [````````````````````````] [``````````````]        
{ msg type } [ addr_from uint16_t ] [====== data bytes ======] [ CRC Bytes ]        
{..........} [........................] [........................] [..............]        
                                                                                           
{ 0000xxxx } [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ]        
{ xxx..|..xxxxx } [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ]        
|     0           1            2            3                         |       |            
\_____________________________________________________________________/       |            
|                                                                             |            
@ -95,12 +123,13 @@ msg type:
/```````````````````````````````````` Задний сигнал машинки с адресацией ````````````````````````````````````\ 
                                                                                    
// Первый байт: (IR_MSG_BACK_TO<<5) | (packSize & IR_MASK_MSG_INFO) — IR_MSG_BACK_TO в битах 7..5, длина 0..31.
                                                                                          
{``````````} [````````````````````````] [````````````````````````] [````````````````````````] [``````````````] 
{ msg type } [ addr_from uint16_t ] [ addr_to uint16_t ] [====== data bytes ======] [ CRC Bytes ] 
{..........} [........................] [........................] [........................] [..............] 
                                                                                                               
{ 0001xxxx } [addr_from_H][addr_from_L] [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ] 
                                                                                                                
{ xxx..|..xxxxx } [addr_from_H][addr_from_L] [addr_to_H][addr_to_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ] 
|     0           1            2              3           4            5                         |       |     
\________________________________________________________________________________________________/       |     
|                                                                                                        |     

386
IrDmaTxStm32.h Normal file
View File

@ -0,0 +1,386 @@
#pragma once
#include "IR_Encoder.h"
#if defined(ARDUINO_ARCH_STM32) && defined(STM32G4xx)
#include <Arduino.h>
#include <HardwareTimer.h>
#if defined(__GNUC__)
#define IR_DMA_TX_HOT __attribute__((always_inline)) inline
#else
#define IR_DMA_TX_HOT inline
#endif
#include "stm32g4xx_hal.h"
/**
* STM32G4: ИК TX через DMA в GPIO BSRR, такт от TIM UPDATE (carrierFrec×2).
*
* Число слотов потоков — параметр шаблона (без макросов), например IrDmaTxStm32<2>.
* По умолчанию: IrDmaTxStm32<> ≡ irproto::kDefaultDmaTxMaxStreams (см. IR_config.h).
*
* Контракт: ref/IR_DMA_TX_backend.md
*/
template<size_t MaxStreams = irproto::kDefaultDmaTxMaxStreams>
class IrDmaTxStm32 {
static_assert(MaxStreams >= 1U, "IrDmaTxStm32: MaxStreams >= 1");
public:
struct StreamCfg {
DMA_Channel_TypeDef* instance = nullptr;
IRQn_Type irq = IRQn_Type(0);
uint32_t dmamuxRequest = 0;
IR_Encoder* enc = nullptr;
uint32_t* dmaWords = nullptr;
uint16_t dmaWordCount = 0;
IR_Encoder::IR_TxGateRun* gateRuns = nullptr;
size_t maxGateRuns = 0;
};
struct Config {
HardwareTimer* timer = nullptr;
uint8_t streamCount = 0;
StreamCfg streams[MaxStreams];
};
bool begin(const Config& cfg) {
cfg_ = cfg;
streamCount_ = cfg.streamCount;
if (cfg_.timer == nullptr || streamCount_ == 0) return false;
if (streamCount_ > MaxStreams) return false;
htim_ = cfg_.timer->getHandle();
if (htim_ == nullptr) return false;
for (uint8_t i = 0; i < streamCount_; i++) {
const StreamCfg& sc = cfg_.streams[i];
if (sc.enc == nullptr || sc.instance == nullptr) return false;
if (sc.dmaWords == nullptr || sc.dmaWordCount < 2U) return false;
if ((sc.dmaWordCount & 1U) != 0U) return false;
if (sc.gateRuns == nullptr || sc.maxGateRuns == 0U) return false;
}
__HAL_RCC_DMA1_CLK_ENABLE();
__HAL_RCC_DMAMUX1_CLK_ENABLE();
for (uint8_t i = 0; i < streamCount_; i++) {
const StreamCfg& sc = cfg_.streams[i];
if (!initStream(streams_[i], sc)) {
return false;
}
}
s_instance = this;
activeCount_ = 0;
for (uint8_t i = 0; i < streamCount_; i++) {
HAL_NVIC_EnableIRQ(streams_[i].dmaIrq);
}
return true;
}
static IrDmaTxStm32<MaxStreams>* instance() {
return s_instance;
}
bool busy() const {
if (streamCount_ == 0) return false;
for (uint8_t i = 0; i < streamCount_; i++) {
if (!streams_[i].active) return false;
}
return true;
}
bool start(IR_Encoder* enc, const uint8_t* packet, uint8_t len) {
if (enc == nullptr) return false;
for (uint8_t i = 0; i < streamCount_; i++) {
if (streams_[i].enc == enc) {
return startStream(streams_[i], packet, len);
}
}
return false;
}
void irqForStream(size_t streamIndex) {
if (streamIndex >= streamCount_) return;
HAL_DMA_IRQHandler(&streams_[streamIndex].hdma);
}
DMA_HandleTypeDef* dmaHandle(size_t streamIndex) {
if (streamIndex >= streamCount_) return nullptr;
return &streams_[streamIndex].hdma;
}
private:
struct TxStream {
DMA_HandleTypeDef hdma{};
DMA_Channel_TypeDef* dmaInstance = nullptr;
IRQn_Type dmaIrq = IRQn_Type(0);
uint32_t dmamuxRequest = 0;
IR_Encoder* enc = nullptr;
GPIO_TypeDef* port = nullptr;
uint16_t mask = 0;
uint32_t setWord = 0;
uint32_t resetWord = 0;
uint32_t* dmaBuf = nullptr;
uint16_t bufLen = 0;
uint16_t halfLen = 0;
IR_Encoder::IR_TxGateRun* runs = nullptr;
size_t maxRuns = 0;
size_t runCount = 0;
size_t runIndex = 0;
uint16_t ticksLeftInRun = 0;
bool carrierPhase = false;
uint32_t totalTicks = 0;
volatile uint32_t ticksOutput = 0;
bool active = false;
void resetWave() {
runIndex = 0;
carrierPhase = false;
ticksOutput = 0;
totalTicks = 0;
runCount = 0;
ticksLeftInRun = 0;
}
IR_DMA_TX_HOT uint32_t nextWord() {
if (runIndex >= runCount) {
return resetWord;
}
const bool gate = runs[runIndex].gate;
if (!gate) {
carrierPhase = false;
} else {
carrierPhase = !carrierPhase;
}
const uint32_t out = (gate && carrierPhase) ? setWord : resetWord;
if (ticksLeftInRun > 0) {
ticksLeftInRun--;
}
if (ticksLeftInRun == 0) {
runIndex++;
if (runIndex < runCount) {
ticksLeftInRun = runs[runIndex].lenTicks;
}
}
return out;
}
IR_DMA_TX_HOT void fill(uint32_t* dst, uint16_t count) {
if (dst == nullptr || count == 0) {
return;
}
do {
*dst++ = nextWord();
} while (--count != 0);
}
void onHalf() {
ticksOutput += halfLen;
fill(&dmaBuf[0], halfLen);
}
void onComplete() {
ticksOutput += halfLen;
fill(&dmaBuf[halfLen], halfLen);
}
void onError() {}
};
static IrDmaTxStm32<MaxStreams>* s_instance;
Config cfg_{};
TIM_HandleTypeDef* htim_ = nullptr;
TxStream streams_[MaxStreams]{};
uint8_t streamCount_ = 0;
volatile uint8_t activeCount_ = 0;
static uint32_t u32ptr(const volatile void* p) {
return (uint32_t)(uintptr_t)p;
}
void startTimerIfNeeded() {
if (htim_ == nullptr) return;
if (activeCount_ != 1) return;
__HAL_TIM_DISABLE_DMA(htim_, TIM_DMA_UPDATE);
__HAL_TIM_CLEAR_FLAG(htim_, TIM_FLAG_UPDATE);
__HAL_TIM_SET_COUNTER(htim_, 0);
__HAL_TIM_ENABLE_DMA(htim_, TIM_DMA_UPDATE);
HAL_TIM_Base_Start(htim_);
}
void stopTimerIfIdle() {
if (htim_ == nullptr) return;
if (activeCount_ != 0) return;
__HAL_TIM_DISABLE_DMA(htim_, TIM_DMA_UPDATE);
HAL_TIM_Base_Stop(htim_);
}
static TxStream* streamFromDma(DMA_HandleTypeDef* hdma) {
if (s_instance == nullptr || hdma == nullptr) return nullptr;
for (uint8_t i = 0; i < s_instance->streamCount_; i++) {
if (hdma == &s_instance->streams_[i].hdma) {
return &s_instance->streams_[i];
}
}
return nullptr;
}
static void dmaHalfCpltCb(DMA_HandleTypeDef* hdma) {
auto* s = streamFromDma(hdma);
if (s == nullptr || !s->active) return;
s->onHalf();
if (s_instance != nullptr && s->ticksOutput >= s->totalTicks) {
s_instance->stopStream(*s);
}
}
static void dmaCpltCb(DMA_HandleTypeDef* hdma) {
auto* s = streamFromDma(hdma);
if (s == nullptr || !s->active) return;
s->onComplete();
if (s_instance != nullptr && s->ticksOutput >= s->totalTicks) {
s_instance->stopStream(*s);
}
}
static void dmaErrorCb(DMA_HandleTypeDef* hdma) {
auto* s = streamFromDma(hdma);
if (s == nullptr) return;
s->onError();
if (s_instance != nullptr) {
s_instance->stopStream(*s);
}
}
bool initStream(TxStream& s, const StreamCfg& chCfg) {
s.enc = chCfg.enc;
s.dmaInstance = chCfg.instance;
s.dmaIrq = chCfg.irq;
s.dmamuxRequest = chCfg.dmamuxRequest;
s.dmaBuf = chCfg.dmaWords;
s.bufLen = chCfg.dmaWordCount;
s.halfLen = (uint16_t)(chCfg.dmaWordCount / 2U);
s.runs = chCfg.gateRuns;
s.maxRuns = chCfg.maxGateRuns;
s.port = (s.enc != nullptr) ? s.enc->getPort() : nullptr;
s.mask = (s.enc != nullptr) ? s.enc->getPinMask() : 0;
s.setWord = (uint32_t)s.mask;
s.resetWord = ((uint32_t)s.mask) << 16;
s.resetWave();
s.hdma.Instance = s.dmaInstance;
s.hdma.Init.Request = s.dmamuxRequest;
s.hdma.Init.Direction = DMA_MEMORY_TO_PERIPH;
s.hdma.Init.PeriphInc = DMA_PINC_DISABLE;
s.hdma.Init.MemInc = DMA_MINC_ENABLE;
s.hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
s.hdma.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
s.hdma.Init.Mode = DMA_CIRCULAR;
s.hdma.Init.Priority = DMA_PRIORITY_HIGH;
HAL_DMA_DeInit(&s.hdma);
if (HAL_DMA_Init(&s.hdma) != HAL_OK) {
return false;
}
s.hdma.XferHalfCpltCallback = dmaHalfCpltCb;
s.hdma.XferCpltCallback = dmaCpltCb;
s.hdma.XferErrorCallback = dmaErrorCb;
s.hdma.XferAbortCallback = nullptr;
return true;
}
bool startStream(TxStream& s, const uint8_t* packet, uint8_t len) {
if (s.enc == nullptr || s.port == nullptr || s.mask == 0) return false;
if (s.active) return false;
if (s.dmaBuf == nullptr || s.bufLen < 2 || s.halfLen == 0) return false;
if (s.runs == nullptr || s.maxRuns == 0) return false;
s.resetWave();
s.runCount = IR_Encoder::buildGateRuns(packet, len, s.runs, s.maxRuns);
if (s.runCount == 0) return false;
uint32_t total = 0;
for (size_t i = 0; i < s.runCount; i++) total += s.runs[i].lenTicks;
s.totalTicks = total;
s.runIndex = 0;
s.ticksLeftInRun = s.runs[0].lenTicks;
s.carrierPhase = false;
s.fill(&s.dmaBuf[0], s.bufLen);
s.port->BSRR = s.resetWord;
const uint32_t dst = u32ptr(&s.port->BSRR);
if (HAL_DMA_Start_IT(&s.hdma, (uint32_t)(uintptr_t)s.dmaBuf, dst, s.bufLen) != HAL_OK) {
return false;
}
s.active = true;
activeCount_++;
startTimerIfNeeded();
return true;
}
void stopStream(TxStream& s) {
if (!s.active) return;
s.active = false;
HAL_DMA_Abort_IT(&s.hdma);
if (s.port != nullptr) {
s.port->BSRR = s.resetWord;
}
if (s.enc != nullptr) {
s.enc->externalFinishSend();
}
if (activeCount_ > 0) activeCount_--;
stopTimerIfIdle();
}
};
template<size_t MaxStreams>
IrDmaTxStm32<MaxStreams>* IrDmaTxStm32<MaxStreams>::s_instance = nullptr;
inline void IrDmaTxStm32_onDmaHandle(DMA_HandleTypeDef* hdma) {
HAL_DMA_IRQHandler(hdma);
}
#elif defined(ARDUINO_ARCH_STM32)
#error "IrDmaTxStm32: добавьте ветку HAL для вашей серии STM32 (сейчас только STM32G4xx)."
#else
template<size_t MaxStreams = irproto::kDefaultDmaTxMaxStreams>
class IrDmaTxStm32 {};
#endif

View File

@ -43,6 +43,8 @@ namespace PacketTypes
inline uint8_t getErrorOther() { return packInfo->err.other; };
inline uint16_t getTunerTime() { return packInfo->rTime; };
inline uint8_t *getDataRawPtr() { return packInfo->buffer; };
/** Полный размер кадра в байтах (как packInfo.packSize); доступен для gotRaw (BasePack). */
inline uint8_t getDataRawSize() { return _getDataRawSize(this); };
};
class Data : public BasePack
@ -61,7 +63,6 @@ namespace PacketTypes
inline uint8_t getDataSize() { return _getDataSize(this); };
inline uint8_t *getDataPrt() { return _getDataPrt(this); };
inline uint8_t getDataRawSize() { return _getDataRawSize(this); };
private:
bool checkAddress() override;
@ -83,7 +84,6 @@ namespace PacketTypes
inline uint8_t getDataSize() { return _getDataSize(this); };
inline uint8_t *getDataPrt() { return _getDataPrt(this); };
inline uint8_t getDataRawSize() { return _getDataRawSize(this); };
private:
bool checkAddress() override;

41082
ref/DMA_no_send__extRX.txt Normal file

File diff suppressed because it is too large Load Diff

14922
ref/DMA_self_frontlog.txt Normal file

File diff suppressed because it is too large Load Diff

64
ref/IR_DMA_TX_backend.md Normal file
View File

@ -0,0 +1,64 @@
# Контракт бэкенда DMA-TX ИК (`IrDmaTxStm32`)
Платформа: **STM32G4**, Arduino STM32. Передача: **DMA memory → GPIO BSRR**, запрос от **TIM UPDATE** (частота `carrierFrec×2` из `IR_Encoder::beginClockOnly`).
### Число потоков (шаблон)
Класс: **`IrDmaTxStm32<MaxStreams>`**. Число слотов в `Config::streams[]` и внутреннем массиве задаётся **в коде**, без `-D` и без макроса до инклюда:
```cpp
constexpr size_t kStreams = 2;
static IrDmaTxStm32<kStreams> dma;
IrDmaTxStm32<kStreams>::Config cfg;
// IRQ: IrDmaTxStm32<kStreams>::instance()
```
По умолчанию: **`IrDmaTxStm32<>`** эквивалентно **`IrDmaTxStm32<irproto::kDefaultDmaTxMaxStreams>`** (`IR_config.h`, обычно 4). Реализация в заголовке (отдельного `.cpp` нет).
## Роль библиотеки
- Разбор пакета в RLE-пробеги: `IR_Encoder::buildGateRuns`.
- Генерация слов для BSRR (несущая/тишина по тикам), предзаполнение буфера и дозаполнение по прерываниям half/complete.
- Настройка канала DMA, DMAMUX, кольцевой режим, старт/стоп DMA и таймера, колбэки HAL.
- В `begin()` только `HAL_NVIC_EnableIRQ` для каналов DMA (без `SetPriority`).
## Роль прошивки (клиента)
### Буферы и размеры
На **каждый** поток в `StreamCfg` клиент передаёт:
| Поле | Смысл |
|------|--------|
| `dmaWords` | Указатель на массив `uint32_t` — слова для записи в BSRR. |
| `dmaWordCount` | Число **слов** (32-bit), **чётное**, ≥ 2. Половина — один «полубуфер» для HT/TC IRQ. |
| `gateRuns` | Массив `IR_Encoder::IR_TxGateRun` для выхода `buildGateRuns`. |
| `maxGateRuns` | Длина этого массива. Должен быть достаточен для самого длинного кадра. |
Память и выравнивание — ответственность клиента; типичные порядки: 4096 слов DMA, 1024 ранов (как в машинке).
### Таймер и DMA
- `HardwareTimer` / тот же TIM, что и `beginClockOnly`, без конкурирующего `attachInterrupt` на UPDATE.
- `instance`, `irq`, `dmamuxRequest` (например `DMA_REQUEST_TIM17_UP`) — из схемы платы; оба потока на одном TIM обычно используют **один** `TIMx_UP` в DMAMUX.
### Приоритеты NVIC
Не задаются в библиотеке. После `begin()` клиент выставляет preempt/sub для `DMA1_ChannelN` (и согласует с приёмом EXTI и др.), например общей функцией вроде `Car_applyInterruptPriorities()`.
### Прерывания DMA
Библиотека **не** объявляет `DMA1_ChannelN_IRQHandler`. В одном `.cpp` прошивки — единственное определение на канал, внутри:
`IrDmaTxStm32<N>::instance()->irqForStream(i)` (тот же **N**, что у объекта бэкенда) или `IrDmaTxStm32_onDmaHandle(hdma)`.
## Контракт `IR_Encoder::setExternalTxBackend`
Подключение: `setExternalTxBackend(startFn, busyFn, ctx)`.
- **`startFn(ctx, enc, packet, len)`** — должен вызвать `IrDmaTxStm32<N>::start(enc, packet, len)` (или обёртку). Возвращает успех старта DMA.
- **`busyFn(ctx)`** — пока возвращает «занято», новая отправка не стартует. У `IrDmaTxStm32<N>::busy()`: **true**, если **все** настроенные потоки в передаче (для двух передатчиков — оба активны); иначе можно запустить второй канал.
## Сбой `begin()`
При ошибке `HAL_DMA_Init` и т.п. `begin()` возвращает `false`, `instance()` не используется для IRQ до успешного `begin()`.

View File

@ -0,0 +1,87 @@
# Формат журнала фронтов ИК (`IR_EDGE_TRACE`)
Включается в `IR_config.h`: раскомментируйте `#define IR_EDGE_TRACE`.
Размер кольца задаётся `IR_EDGE_TRACE_CAPACITY` (по умолчанию 512 записей).
Память: примерно `IR_EDGE_TRACE_CAPACITY × 6` байт на экземпляр `IR_DecoderRaw`.
## Назначение
В ISR на каждый аппаратный фронт на линии приёмника пишется запись: абсолютное время `micros()`, уровень линии после фронта, флаги. Это **отдельное** кольцо от `subBuffer`: при переполнении `subBuffer` фронты в журнале всё равно сохраняются, пока не заполнится это кольцо.
При **передаче ИК по DMA** на STM32 важно, чтобы **прерывание приёма (EXTI)** имело **более высокий приоритет NVIC**, чем DMA канала передачи — иначе метки времени и сам поток фронтов в логе искажаются. См. **[`IR_DMA_ISR_signal_analysis.md`](../IR_DMA_ISR_signal_analysis.md)** (раздел 2.1).
## Вывод в Serial
При включённом `IR_EDGE_TRACE` протокол **сам** сбрасывает накопленные фронты в конце каждого `IR_DecoderRaw::tick()` (и на ветке «subBuffer пуст»): в цикле вызывается `edgeTraceFlushChunk(Serial, 48)`, пока в кольце есть записи.
Вручную тот же смысл: `edgeTraceFlushChunk(Print &out, maxRec)` печатает **ровно одну строку** (если есть что выгрузить; при пустом кольце выход без печати):
1. Символ перевода строки `\n` (отделяет блок от предыдущего вывода).
2. Литеральный префикс **`@IRF1v1:`** (удобно grep-ать; не используйте этот текст в других `Serial.print`, чтобы строки не сливались).
3. **Нижний регистр hex** без пробелов: полезная нагрузка бинарного блока ниже.
4. `\n` в конце.
Другой текст (например `IR raw:` из `IRDEBUG_SERIAL_PACK`) не содержит `@IRF1v1:`, поэтому визуально и по парсеру блоки разделимы.
Если авто-сброс в `tick()` отключён или нужен другой `Print`, вызывайте `edgeTraceFlushChunk` в цикле, пока возвращаемое значение > 0.
## Бинарная полезная нагрузка (до кодирования в hex)
Все многобайтовые целые — **little-endian**, порядок байт от младшего к старшему.
| Смещение | Размер | Поле |
|----------|--------|------|
| 0 | 1 | **meta** |
| 1 | 2 | **count** — число записей в этой строке (`uint16_t`) |
| 3 | `count × 6` | Массив записей |
### meta (байт)
| Бит | Значение |
|-----|----------|
| 0 | **overflow**: кольцо хотя бы раз переполнилось с момента последнего `edgeTraceClear()`; новые фронты терялись, пока не освободилось место. Сбрасывается только `edgeTraceClear()`. |
| 1 | **truncated**: после этой выгрузки в буфере ещё есть записи (chunk урезан лимитом `maxRec` или внутренним максимумом 64). |
Биты 27 зарезервированы (0).
### Одна запись (6 байт)
| Смещение в записи | Размер | Поле |
|-------------------|--------|------|
| 0 | 4 | **t_us** — значение `micros()` на момент фронта (`uint32_t`). При переполнении `micros()` (~70 мин) разницы между соседними записями всё ещё корректны, если обрабатывать как unsigned. |
| 4 | 1 | **level** — уровень входа приёмника после фронта: `0` = LOW, `1` = HIGH (как `port->IDR & mask` в ISR). |
| 5 | 1 | **flags** |
| | | бит 0 **SKIP_DECODE** (`IR_EDGE_TRACE_F_SKIP_DECODE`): фронт записан, но в `subBuffer` **не** попал, потому что был активен `isPairSending` (пара передаёт). Алгоритм декодирования этот фронт не видит. |
## Минимальный разбор (Python 3)
```python
import binascii, re
def parse_irf1_line(line: str):
m = re.search(r"@IRF1v1:([0-9a-f]+)\s*$", line.strip())
if not m:
return None
raw = binascii.unhexlify(m.group(1))
meta, cnt_lo, cnt_hi = raw[0], raw[1], raw[2]
count = cnt_lo | (cnt_hi << 8)
recs = []
p = 3
for _ in range(count):
t = raw[p] | (raw[p+1]<<8) | (raw[p+2]<<16) | (raw[p+3]<<24)
level, flags = raw[p+4], raw[p+5]
recs.append((t, level, flags))
p += 6
return {
"overflow": bool(meta & 1),
"truncated": bool(meta & 2),
"count": count,
"records": recs,
}
```
## Рекомендации по съёму
- При очень плотном потоке фронтов кольцо всё же может переполниться до следующего `tick()` — увеличьте `IR_EDGE_TRACE_CAPACITY` или уменьшите нагрузку на ISR.
- Для «чистого» лога отключите или сильно урежьте `IRDEBUG_SERIAL_PACK`, иначе объём Serial будет очень большим.
- Для полного сброса состояния перед тестом: `edgeTraceClear()`.

289
ref/ISR_self.txt Normal file
View File

@ -0,0 +1,289 @@
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR sendTimer()
IR Laser();
IR SKIP LASER
IR sendTimer()
IR irSend()
IR raw: => ERROR: TIMEOUT, rx_data_size = 10, but only 10 bytes received
IR hex: CA 00 00 FD E8 58 00 00 DD D8
IR raw: 110 01010 101 00000000 101 00000000 100 11111101 010 11101000 101 01011000 101 00000000 101 00000000 100 11011101 010 11011000 => OK: SendInfo_v1_1, Empty_Command, Empty_Command
IR hex: CA 00 00 FD E8 58 00 00 DD D8

17170
ref/ISR_self_frontlog.txt Normal file

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

13
ref/point response.txt Normal file
View File

@ -0,0 +1,13 @@
IR raw: 110 01001 011 01111101 011 00100110 101 00000000 100 00000000 101 01110110 101 00100111 010 10011100 101 01101100 => OK: Laser_ON, LED_Left_BlinkTest
IR hex: C9 7D 26 00 00 76 27 9C 6C
IR raw: 110 01001 011 01111101 011 00100110 101 00000000 100 00000000 101 01110110 101 00100111 010 10011100 101 01101100 => OK: Laser_ON, LED_Left_BlinkTest

721
tools/ir_decoder_sim.py Normal file
View File

@ -0,0 +1,721 @@
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
"""
Офлайн-симуляция IR_DecoderRaw::tick + writeToBuffer по журналу @IRF1v1:
См. ref/IR_EDGE_TRACE_FORMAT.md
При FRAME_END: сводка (чистые биты / burst / отброшенные фронты), список точечных
исправлений (преамбула, пропуск такта, поджатие low/high, sync), при crc_ok=False —
разбор несовпадения CRC; в первой строке пакет как hex= и bin= (8 бит на байт MSB-first,
байты через пробел); отдельная строка «синхро» — счётчик ошибок 1-го бита тройки (как
err_syncBit в прошивке) и принятые тройки sync-битов между байтами (2-й и 3-й в прошивке
не сверяются с шаблоном, только пишутся в поток — их значения для наглядности сдвига).
WRONG_PACK_SYNC — отдельное событие с причиной и тем же блоком «синхро».
Флаг -v/--verbose: дополнительно каждая строка для «чистого» бита (aroundRise) и
отброшенных фронтов; без флага эти события только в счётчиках сводки.
Не моделирует IRDEBUG_SERIAL_SOFT_REJECT (жёсткий Wrong sync).
Таймауты: между фронтами, если gap > IR_timeout*2 и isRecive — checkTimeout.
"""
from __future__ import annotations
import argparse
import binascii
import os
import re
import sys
from dataclasses import dataclass, field
from typing import List, Tuple
# --- IR_config.h (как в прошивке, целочисленно) ---
CARRIER_FREC = 38000
CARRIER_PERIOD = 1000000 // CARRIER_FREC
BIT_ACTIVE_TAKTS = 25
BIT_PAUSE_TAKTS = 12
BIT_TAKTS = BIT_ACTIVE_TAKTS + BIT_PAUSE_TAKTS
BIT_TIME = BIT_TAKTS * CARRIER_PERIOD
TOLERANCE = 300
SYNCBITS = 3
BIT_PER_BYTE = 8
MSGBYTES = 1
CRC_BYTES = 2
POLY1 = 0x31
POLY2 = 0x8C
IR_MASK_MSG_INFO = 0x1F
PREAMB_PULSE = 3
PREAMB_FRONTS = PREAMB_PULSE * 2
BYTE_PER_PACK = 31
DATA_BYTE_SIZE_MAX = MSGBYTES + 2 + 2 + BYTE_PER_PACK + CRC_BYTES
FREE_FREC = False
SKIP_DECODE_FLAG = 0x01
# Myagkie tsveta dlya terminala (256-color), ne iarkie default 31/32
_ANSI_GREEN = "\033[38;5;107m" # priglushennyj zelenyj (ne iarkij 32)
_ANSI_RED = "\033[38;5;174m" # pylno-rozovyj / myagkij krasnyj (ne iarkij 31)
_ANSI_RESET = "\033[0m"
# Zolotistyj / birjuzovyj + zhirnyj dlya hex i bin paketa v stroke FRAME_END
_HEX_PACKET_FG = "\033[1;38;5;222m"
_BIN_PACKET_FG = "\033[1;38;5;109m"
def _bytes_bin_msb(data: bytes) -> str:
"""8 bit na bajt (MSB pervyj, kak v writeToBuffer), bajty cherez probel."""
return " ".join(f"{b:08b}" for b in data)
def _use_terminal_color() -> bool:
if os.environ.get("NO_COLOR"):
return False
try:
return sys.stdout.isatty()
except Exception:
return False
def _colorize_block(text: str, ok: bool, enabled: bool) -> str:
if not enabled:
return text
code = _ANSI_GREEN if ok else _ANSI_RED
return f"{code}{text}{_ANSI_RESET}"
def _highlight_hex_bin_in_frame_line(line: str, ok: bool, enabled: bool) -> str:
"""Odna stroka s FRAME_END: vydeljaet hex= i bin=."""
if not enabled or "FRAME_END" not in line:
return line
parent = _ANSI_GREEN if ok else _ANSI_RED
after = "\033[22m" + parent
spans: list[tuple[int, int, str]] = []
mhx = re.search(r"hex=([0-9a-fA-F]+)", line)
if mhx:
spans.append((mhx.start(1), mhx.end(1), _HEX_PACKET_FG))
mbn = re.search(r"bin=([01 ]+)$", line)
if mbn:
spans.append((mbn.start(1), mbn.end(1), _BIN_PACKET_FG))
if not spans:
return line
spans.sort(key=lambda t: t[0])
out: list[str] = []
last = 0
for s, e, col in spans:
out.append(line[last:s])
out.append(col + line[s:e] + after)
last = e
out.append(line[last:])
return "".join(out)
def _highlight_frame_end_payloads(ev: str, ok: bool, enabled: bool) -> str:
"""Vo vseh strokah FRAME_END vydeljaet hex= i bin= (v tom chisle povtor svodki v konce)."""
if not enabled:
return ev
return "\n".join(_highlight_hex_bin_in_frame_line(L, ok, enabled) for L in ev.split("\n"))
def _packet_event_tone(ev: str) -> str | None:
"""'ok' | 'bad' | None — dlya pokrashki celogo bloka sobytija."""
head = ev.split("\n", 1)[0]
if "FRAME_END" in head:
if "crc_ok=True" in head:
return "ok"
if "crc_ok=False" in head:
return "bad"
if "WRONG_PACK_SYNC" in head:
return "bad"
return None
def rise_time_max(rise_sync: int) -> int:
return rise_sync + TOLERANCE
def rise_time_min(rise_sync: int) -> int:
return rise_sync - TOLERANCE
def ir_timeout_us(rise_sync: int) -> int:
return rise_time_max(rise_sync) * (8 + SYNCBITS + 1)
def around_rise(t: int, rise_sync: int) -> bool:
return rise_time_min(rise_sync) < t < rise_time_max(rise_sync)
def ceil_div(val: int, divider: int) -> int:
ret = val // divider
if (val << 4) // divider - (ret << 4) >= 8:
ret += 1
return ret
def crc8(data: bytes, start: int, end: int, poly: int) -> int:
crc = 0xFF
for i in range(start, end):
crc ^= data[i]
for _ in range(8):
if crc & 0x80:
crc = ((crc << 1) ^ poly) & 0xFF
else:
crc = (crc << 1) & 0xFF
return crc
def crc_compute_bytes(data: bytearray, pack_size: int) -> Tuple[int, int, int]:
"""Ожидаемые байты CRC: (crc1_hi, crc2_lo, len_payload) или (-1,-1,-1) при неверном pack_size."""
if pack_size < 1 + CRC_BYTES or pack_size > DATA_BYTE_SIZE_MAX:
return (-1, -1, -1)
ln = pack_size - CRC_BYTES
c1 = crc8(bytes(data), 0, ln, POLY1)
c2 = crc8(bytes(data), 0, ln + 1, POLY2)
return (c1 & 0xFF, c2 & 0xFF, ln)
def crc_check(data: bytearray, pack_size: int) -> bool:
ln = pack_size - CRC_BYTES
c1 = crc8(bytes(data), 0, ln, POLY1)
c2 = crc8(bytes(data), 0, ln + 1, POLY2)
crc = ((c1 << 8) & ~0xFF) | (c2 & 0xFF)
return data[ln] == ((crc >> 8) & 0xFF) and data[ln + 1] == (crc & 0xFF)
def crc_failure_lines(data: bytearray, pack_size: int) -> List[str]:
"""Подробности при несовпадении CRC."""
out: List[str] = []
exp_hi, exp_lo, ln = crc_compute_bytes(data, pack_size)
if ln < 0:
out.append(f" некорректный pack_size={pack_size} (ожидается 1..{DATA_BYTE_SIZE_MAX})")
return out
got_hi = data[pack_size - 2]
got_lo = data[pack_size - 1]
hdr = data[0]
msg_t = (hdr >> 5) & 0x07
out.append(
f" байт[0]=0x{hdr:02x} тип_сообщения={msg_t} заявл._длинаадра={hdr & IR_MASK_MSG_INFO} байт"
)
out.append(
f" правило CRC: crc8(data[0..{ln - 1}], poly1=0x{POLY1:02x}) -> байт[{ln}]; "
f"crc8(data[0..{ln}], poly2=0x{POLY2:02x}) -> байт[{ln + 1}]"
)
out.append(f" ожидалось: {exp_hi:02x} {exp_lo:02x} принято в кадре: {got_hi:02x} {got_lo:02x}")
if got_hi != exp_hi:
out.append(
f" первый байт CRC не совпал - искажены данные [0..{ln - 1}] и/или этот байт CRC"
)
if got_lo != exp_lo:
out.append(
" второй байт CRC не совпал - в poly2 входит уже первый байт CRC; типично сдвиг битовой границы"
)
pl = data[:ln].hex()
out.append(f" полезная нагрузка без CRC ({ln} байт): {pl}")
return out
@dataclass
class EdgeRec:
t_us: int
level: int # 0/1 после фронта
flags: int
def parse_irf1_lines(text: str) -> List[EdgeRec]:
out: List[EdgeRec] = []
pat = re.compile(r"@IRF1v1:([0-9a-fA-F]+)\s*")
for m in pat.finditer(text):
hx = m.group(1)
if len(hx) % 2:
continue
try:
raw = binascii.unhexlify(hx)
except binascii.Error:
continue
if len(raw) < 3:
continue
meta = raw[0]
count = raw[1] | (raw[2] << 8)
need = 3 + count * 6
if len(raw) < need or count > 2000:
continue
p = 3
for _ in range(count):
t = raw[p] | (raw[p + 1] << 8) | (raw[p + 2] << 16) | (raw[p + 3] << 24)
lvl = raw[p + 4]
flg = raw[p + 5]
out.append(EdgeRec(t, lvl & 1, flg))
p += 6
if meta & 1:
pass # overflow — запись могла обрезаться
return out
@dataclass
class DecoderSim:
prev_rise: int = 0
prev_fall: int = 0
rise_period: int = 0
high_time: int = 0
low_time: int = 0
last_edge_time: int = 0
preamb_front_counter: int = 0
is_preamb: bool = False
is_recive: bool = False
is_recive_raw: bool = False
is_wrong_pack: bool = False
is_buffer_overflow: bool = False
rise_sync_time: int = BIT_TIME
high_count: int = 0
low_count: int = 0
all_count: int = 0
i_data_buffer: int = 0
buf_bit_pos: int = 0
next_control_bit: int = BIT_PER_BYTE
is_data: bool = True
i_sync_bit: int = 0
err_sync_bit: int = 0
data_buffer: bytearray = field(default_factory=lambda: bytearray(DATA_BYTE_SIZE_MAX))
pack_size: int = 0
errors_other: int = 0
events: List[str] = field(default_factory=list)
verbose: bool = False
"""Подстроеки/исправления как в IR_DecoderRaw::tick (за текущий пакет)."""
packet_fixes: List[str] = field(default_factory=list)
_fatal_sync_event_sent: bool = False
stat_clean_bits: int = 0
stat_burst_edges: int = 0
stat_debounce_rise: int = 0
stat_debounce_fall: int = 0
# Mezhdu bajtami: trojki sync-bitov (kak v writeToBuffer); oshibka schetaetsja tolko za 1-j bit
stat_sync_first_error: int = 0
sync_groups: List[str] = field(default_factory=list)
sync_bits_current_group: List[int] = field(default_factory=list)
def _fix(self, msg: str) -> None:
self.packet_fixes.append(msg)
def _clear_packet_state(self) -> None:
self.packet_fixes.clear()
self._fatal_sync_event_sent = False
self.stat_clean_bits = 0
self.stat_burst_edges = 0
self.stat_debounce_rise = 0
self.stat_debounce_fall = 0
self.stat_sync_first_error = 0
self.sync_groups.clear()
self.sync_bits_current_group.clear()
def _sync_bit_consumed(self, bit_val: int) -> None:
"""Odin prinjatyj sync-bit (bufBitPos++ v vetke sync v proshivke)."""
self.sync_bits_current_group.append(bit_val & 1)
if len(self.sync_bits_current_group) == SYNCBITS:
self.sync_groups.append("".join(str(b) for b in self.sync_bits_current_group))
self.sync_bits_current_group.clear()
def _sync_summary_lines(self, *, with_firmware_note: bool = False) -> List[str]:
"""Stroki svodki po sinhrobitam dlya FRAME_END i WRONG_PACK_SYNC."""
sg = "/".join(self.sync_groups) if self.sync_groups else ""
lines = [
f" синхро: ошибок_1-го_битаак_в_IR_DecoderRaw)={self.stat_sync_first_error}; "
f"полныхроек={len(self.sync_groups)}; биты_троек={sg}"
]
if self.sync_bits_current_group:
tail = "".join(str(b) for b in self.sync_bits_current_group)
lines.append(f" синхро: незавершённая_тройка (уже приняты биты): {tail}")
if with_firmware_note:
lines.append(
" синхро: в прошивке при ошибке считается только случай «1-й бит тройки совпал с последним "
"data-битом» (errors.other++, err_syncBit); 2-й и 3-й sync-биты не сравниваются с эталоном."
)
return lines
def _emit_wrong_sync_fatal(self, t: int) -> None:
lines = [
f"t={t} WRONG_PACK_SYNC (аналог ERROR: Wrong sync bit в прошивке, err_sync_bit>={SYNCBITS})"
]
if self.packet_fixes:
lines.append(" подстройки и исправления до ошибки:")
for fx in self.packet_fixes:
lines.append(f" - {fx}")
lines.extend(self._sync_summary_lines(with_firmware_note=True))
lines.append(
" причина фатала: повторы неверного 1-го sync-бита накапливают err_syncBit до порога syncBits."
)
self.events.append("\n".join(lines))
def first_rx(self) -> None:
self.is_buffer_overflow = False
self.pack_size = 0
self.buf_bit_pos = 0
self.is_data = True
self.i_data_buffer = 0
self.next_control_bit = BIT_PER_BYTE
self.i_sync_bit = 0
self.err_sync_bit = 0
self.is_wrong_pack = False
self.data_buffer[:] = bytes(DATA_BYTE_SIZE_MAX)
self.rise_sync_time = BIT_TIME
self.stat_sync_first_error = 0
self.sync_groups.clear()
self.sync_bits_current_group.clear()
def listen_start(self, now: int) -> None:
to = ir_timeout_us(self.rise_sync_time)
if self.is_recive_raw and (now - self.prev_rise) > to * 2:
self.events.append(f"t={now} listenStart abort raw (gap from prev_rise)")
self.is_recive_raw = False
self._clear_packet_state()
self.first_rx()
def check_timeout(self, now: int) -> None:
if not self.is_recive:
return
to = ir_timeout_us(self.rise_sync_time)
if now - self.last_edge_time > to * 2:
self.events.append(f"t={now} checkTimeout (gap since last edge)")
self.is_recive = False
self.last_edge_time = now
def write_to_buffer(self, bit_val: int) -> None:
if self.i_data_buffer > DATA_BYTE_SIZE_MAX * 8:
self.is_buffer_overflow = True
self._fix("переполнение буфера битов (writeToBuffer: i_dataBuffer > dataByteSizeMax*8)")
if self.is_buffer_overflow or self.is_preamb or self.is_wrong_pack:
self.is_recive = False
self.is_recive_raw = False
return
if self.buf_bit_pos == self.next_control_bit:
self.next_control_bit += SYNCBITS if self.is_data else BIT_PER_BYTE
self.is_data = not self.is_data
self.i_sync_bit = 0
self.err_sync_bit = 0
if self.is_data:
bi = self.i_data_buffer // 8
self.data_buffer[bi] |= (bit_val & 1) << (7 - (self.i_data_buffer % 8))
self.i_data_buffer += 1
self.buf_bit_pos += 1
else:
if self.i_sync_bit == 0:
prev_bit = (
self.data_buffer[(self.i_data_buffer - 1) // 8]
>> (7 - (self.i_data_buffer - 1) % 8)
) & 1
if bit_val != prev_bit:
self.buf_bit_pos += 1
self.i_sync_bit += 1
self._sync_bit_consumed(bit_val)
else:
self.i_sync_bit = 0
self.errors_other += 1
self.err_sync_bit += 1
self.stat_sync_first_error += 1
self._fix(
f"sync: 1-й sync-бит совпал с последним data-битом (data={prev_bit}); "
f"err_sync_bit={self.err_sync_bit}/{SYNCBITS} (как в прошивке)"
)
if self.err_sync_bit >= SYNCBITS:
self.is_wrong_pack = True
if not self._fatal_sync_event_sent:
self._fatal_sync_event_sent = True
self._emit_wrong_sync_fatal(self.last_edge_time)
else:
self.buf_bit_pos += 1
self.i_sync_bit += 1
self._sync_bit_consumed(bit_val)
self.is_wrong_pack = self.err_sync_bit >= SYNCBITS
if self.is_data and not self.is_wrong_pack:
if self.i_data_buffer == 8 * MSGBYTES:
self.pack_size = self.data_buffer[0] & IR_MASK_MSG_INFO
if self.pack_size and self.i_data_buffer == self.pack_size * BIT_PER_BYTE:
ok = crc_check(self.data_buffer, self.pack_size)
raw = self.data_buffer[: self.pack_size]
hx = raw.hex()
bstr = _bytes_bin_msb(raw)
frame_line = (
f"t={self.last_edge_time} FRAME_END pack={self.pack_size} crc_ok={ok} hex={hx} bin={bstr}"
)
sync_lines = self._sync_summary_lines()
tick_summary = (
f" сводка тактов: чистых_битов_aroundRise={self.stat_clean_bits}, "
f"фронтов_с_burst-коррекцией={self.stat_burst_edges}, "
f"отброшенныхронтов_up={self.stat_debounce_rise}, down={self.stat_debounce_fall}"
)
def _frame_summary_block() -> List[str]:
return [frame_line, *sync_lines, tick_summary]
lines: List[str] = []
lines.extend(_frame_summary_block())
if self.packet_fixes:
if self.verbose:
lines.append(
" подстройки и исправления за пакет, подробный режим (-v) (аналог IR_DecoderRaw::tick):"
)
else:
lines.append(
" подстройки и исправления за пакет (преамбула, пропуск такта, burst, sync; "
"без строк по каждому «чистому» биту — включите -v):"
)
for fx in self.packet_fixes:
lines.append(f" - {fx}")
else:
lines.append(
" дополнительных исправлений нет (см. сводку; для строк по каждому биту: -v/--verbose)"
)
if not ok:
lines.append(" неуспешный пакет — причина:")
lines.extend(crc_failure_lines(self.data_buffer, self.pack_size))
lines.append(" --- сводка пакета (конец записи) ---")
lines.extend(_frame_summary_block())
self.events.append("\n".join(lines))
self.is_recive = False
self.is_recive_raw = False
self._clear_packet_state()
self.first_rx()
def tick_edge(self, t: int, level: int) -> None:
"""Один фронт: level = состояние линии ПОСЛЕ фронта (как dir в C++)."""
self.listen_start(t)
self.last_edge_time = t
rising = level == 1
if rising:
cond = (t - self.prev_rise > rise_time_max(self.rise_sync_time) // 4) or self.high_count or self.low_count
if cond:
self.rise_period = t - self.prev_rise
self.high_time = t - self.prev_fall
self.low_time = self.prev_fall - self.prev_rise
self.prev_rise = t
else:
self.errors_other += 1
self.stat_debounce_rise += 1
if self.verbose:
self._fix(
f"t={t} отброшен фронт ↑: слишком короткий интервал до предыдущего ↑ "
f"(<= riseTimeMax/4 при hc=lc=0), errors.other++"
)
else:
if t - self.prev_fall > rise_time_min(self.rise_sync_time) // 4:
self.prev_fall = t
else:
self.errors_other += 1
self.stat_debounce_fall += 1
if self.verbose:
self._fix(
f"t={t} отброшен фронт ↓: слишком короткий интервал до предыдущего ↓ (<= riseTimeMin/4), errors.other++"
)
rt = self.rise_sync_time
to = ir_timeout_us(rt)
if t > self.prev_rise and (t - self.prev_rise) > to * 2 and not self.is_recive_raw:
self.preamb_front_counter = PREAMB_FRONTS - 1
self.is_preamb = True
self.is_recive = True
self.is_recive_raw = True
self.is_wrong_pack = False
self._clear_packet_state()
self.events.append(f"t={t} PACKET_START (long idle)")
if self.preamb_front_counter:
if rising and self.rise_period < to:
if self.rise_period < rise_time_min(rt) // 2:
self.preamb_front_counter += 2
self.errors_other += 1
self._fix(
f"преамбула: «рваная единица» risePeriod={self.rise_period} us < riseTimeMin/2 "
f"({rise_time_min(rt) // 2} us) -> preambFrontCounter += 2, errors.other++"
)
elif FREE_FREC:
old = self.rise_sync_time
self.rise_sync_time = (self.rise_sync_time + self.rise_period // 2) // 2
self._fix(
f"преамбула: подстройка riseSyncTime {old}->{self.rise_sync_time} us (freeFrec)"
)
self.preamb_front_counter -= 1
else:
if self.is_preamb:
self.is_preamb = False
half = self.rise_period // 2
self.prev_rise += half
self._fix(
f"после преамбулы: prev_rise += risePeriod/2 (+{half} us) - фазовая привязка к центру бита"
)
return
if self.is_preamb:
return
if self.rise_period > to or self.is_buffer_overflow or self.rise_period < rise_time_min(rt) or self.is_wrong_pack:
if self.is_recive and rising and (self.rise_period > to or self.rise_period < rise_time_min(rt)):
reason = (
f"risePeriod={self.rise_period} us: "
+ (f"> IR_timeout={to} us " if self.rise_period > to else "")
+ (f"< riseTimeMin={rise_time_min(rt)} us " if self.rise_period < rise_time_min(rt) else "")
)
self._fix(f"t={t} пропуск такта (goto END): {reason.strip()}")
return
if not rising:
return
self.high_count = 0
self.low_count = 0
self.all_count = 0
invert_err = False
rt = self.rise_sync_time
if around_rise(self.rise_period, rt):
self.stat_clean_bits += 1
bit = 1 if self.high_time > self.low_time else 0
if self.verbose:
self._fix(
f"t={t} «чистый» бит: aroundRise (risePeriod={self.rise_period} us в [{rise_time_min(rt)}..{rise_time_max(rt)}]), "
f"highTime={self.high_time} lowTime={self.low_time} us -> bit {bit}"
)
self.write_to_buffer(bit)
else:
self.stat_burst_edges += 1
self.high_count = ceil_div(self.high_time, rt)
self.low_count = ceil_div(self.low_time, rt)
self.all_count = ceil_div(self.rise_period, rt)
self._fix(
f"t={t} пропуск такта / растяжение: risePeriod={self.rise_period} us вне aroundRise "
f"[{rise_time_min(rt)}..{rise_time_max(rt)}]; "
f"ceil_div: highTime/{rt}->{self.high_count}, lowTime/{rt}->{self.low_count}, risePeriod/{rt}->{self.all_count}"
)
if self.high_count == 0 and self.high_time > rt // 3:
self.high_count += 1
self.errors_other += 1
self._fix(
f"доп. коррекция: highCount был 0 при highTime={self.high_time} > riseTime/3 ({rt // 3}) -> highCount++"
)
if self.low_count + self.high_count > self.all_count:
lo, hi, ac = self.low_count, self.high_count, self.all_count
if self.low_count > self.high_count:
self.low_count = self.all_count - self.high_count
self._fix(
f"поджатие: low+high>{ac} и low>high -> lowCount {lo}->{self.low_count} (лишние нули)"
)
elif self.low_count < self.high_count:
self.high_count = self.all_count - self.low_count
self._fix(
f"поджатие: low+high>{ac} и low<high -> highCount {hi}->{self.high_count} (лишние единицы)"
)
elif self.low_count == self.high_count:
invert_err = True
self.errors_other += self.all_count
self._fix(
f"поджатие: low==high при low+high>{ac} -> invertErr (последний из low-цикла пишется как 1)"
)
i = 0
while i < self.low_count and (8 - i):
if i == self.low_count - 1 and invert_err:
invert_err = False
self.write_to_buffer(1)
else:
self.write_to_buffer(0)
i += 1
i = 0
while i < self.high_count and (8 - i):
if i == self.high_count - 1 and invert_err:
invert_err = False
self.write_to_buffer(0)
else:
self.write_to_buffer(1)
i += 1
def timing_stats(edges: List[EdgeRec]) -> None:
dts: List[int] = []
for i in range(1, len(edges)):
d = edges[i].t_us - edges[i - 1].t_us
if 0 <= d < 1_000_000:
dts.append(d)
if not dts:
print("Нет интервалов для статистики.")
return
dts.sort()
def pct(p: float) -> int:
return dts[int(len(dts) * p)]
print("--- Inter-edge deltas in log (us) ---")
print(f" N={len(dts)} min={dts[0]} p50={pct(0.5)} p90={pct(0.9)} max={dts[-1]}")
print(
f" bitTime(ref)~{BIT_TIME} us aroundRise window ({rise_time_min(BIT_TIME)}..{rise_time_max(BIT_TIME)}) us"
)
# грубые корзины
buckets = [0, 0, 0, 0, 0]
for d in dts:
if d < 200:
buckets[0] += 1
elif d < 600:
buckets[1] += 1
elif d < 1200:
buckets[2] += 1
elif d < 3000:
buckets[3] += 1
else:
buckets[4] += 1
print(f" корзины [0-200) [200-600) [600-1200) [1200-3000) [3000+): {buckets}")
def main() -> int:
ap = argparse.ArgumentParser(description="Симуляция IR decode по @IRF1v1 логу")
ap.add_argument("logfile", nargs="?", default=None, help="Текстовый лог с @IRF1v1:")
ap.add_argument("--include-skipped", action="store_true", help="Подмешивать фронты с SKIP_DECODE (обычно нет)")
ap.add_argument("--max-events", type=int, default=80, help="Макс. событий FRAME_START/END в отчёте")
ap.add_argument(
"--no-color",
action="store_true",
help="Bez ANSI-tsvetov (ili zadajte NO_COLOR v okruzhenii)",
)
ap.add_argument(
"-v",
"--verbose",
action="store_true",
help="Podrobnyj vyvod: kazhdyj chistyj bit (aroundRise), otbrosy frontov; inache tolko svodka",
)
args = ap.parse_args()
if not args.logfile:
print("Укажите путь к логу, например: python tools/ir_decoder_sim.py ref/ISR_self_frontlog.txt")
return 1
text = open(args.logfile, "r", encoding="utf-8", errors="replace").read()
raw_edges = parse_irf1_lines(text)
edges = [e for e in raw_edges if args.include_skipped or not (e.flags & SKIP_DECODE_FLAG)]
edges.sort(key=lambda e: (e.t_us, id(e)))
print(f"Записей фронтов (после фильтра SKIP): {len(edges)} (всего распарсено: {len(raw_edges)})")
timing_stats(edges)
dec = DecoderSim(verbose=args.verbose)
for e in edges:
to_us = ir_timeout_us(dec.rise_sync_time)
if dec.is_recive and dec.last_edge_time > 0 and (e.t_us - dec.last_edge_time) > to_us * 2:
dec.check_timeout(e.t_us)
dec.tick_edge(e.t_us, e.level)
print("--- События декодера (первые N), пакеты разделены пустой строкой ---")
slice_ev = dec.events[: args.max_events]
first_packet = True
use_color = _use_terminal_color() and not args.no_color
for ev in slice_ev:
head = ev.split("\n", 1)[0]
if "PACKET_START" in head:
if not first_packet:
print()
first_packet = False
tone = _packet_event_tone(ev)
if tone is not None:
ok = tone == "ok"
ev_out = _highlight_frame_end_payloads(ev, ok=ok, enabled=use_color)
print(_colorize_block(ev_out, ok=ok, enabled=use_color))
else:
print(ev)
if len(dec.events) > args.max_events:
print(f"... всего событий: {len(dec.events)}")
print(f"errors_other={dec.errors_other} wrong_pack_end={dec.is_wrong_pack} recive={dec.is_recive}")
return 0
if __name__ == "__main__":
sys.exit(main())