diff --git a/.clang-format b/.clang-format
index 7de08030..ffaab188 100644
--- a/.clang-format
+++ b/.clang-format
@@ -1,96 +1,20 @@
----
Language: Cpp
-# BasedOnStyle: LLVM
-AccessModifierOffset: -4
-AlignAfterOpenBracket: Align
+BasedOnStyle: Mozilla
+IndentWidth: 4
+ColumnLimit: 120
+Standard: c++20
+IndentExternBlock: NoIndent
+AlwaysBreakAfterDefinitionReturnType: None
+BreakAfterReturnType: None
+AllowShortFunctionsOnASingleLine: All
AlignConsecutiveAssignments: true
+AlignConsecutiveBitFields: true
AlignConsecutiveDeclarations: true
-AlignEscapedNewlines: Left
-AlignOperands: true
+AlignConsecutiveMacros: true
+AlignConsecutiveShortCaseStatements: { Enabled: true }
+AlignEscapedNewlines: LeftWithLastLine
AlignTrailingComments: true
-AllowAllParametersOfDeclarationOnNextLine: false
-AllowShortBlocksOnASingleLine: Never
-AllowShortCaseLabelsOnASingleLine: false
-AllowShortFunctionsOnASingleLine: Inline
-AllowShortIfStatementsOnASingleLine: Never
-AllowShortLoopsOnASingleLine: false
-AlwaysBreakAfterDefinitionReturnType: None
-AlwaysBreakAfterReturnType: None
-AlwaysBreakBeforeMultilineStrings: false
-AlwaysBreakTemplateDeclarations: Yes
-BinPackArguments: false
-BinPackParameters: false
-BraceWrapping:
- AfterCaseLabel: true
- AfterClass: true
- AfterControlStatement: true
- AfterEnum: true
- AfterFunction: true
- AfterNamespace: true
- AfterStruct: true
- AfterUnion: true
- BeforeCatch: true
- BeforeElse: true
- IndentBraces: false
- SplitEmptyFunction: false
- SplitEmptyRecord: false
- SplitEmptyNamespace: false
- AfterExternBlock: false # Keeps the contents un-indented.
-BreakBeforeBinaryOperators: None
-BreakBeforeBraces: Custom
-BreakBeforeTernaryOperators: true
-BreakConstructorInitializers: AfterColon
-# BreakInheritanceList: AfterColon
-BreakStringLiterals: true
-ColumnLimit: 120
-CommentPragmas: '^ (coverity|pragma:)'
-CompactNamespaces: false
-ConstructorInitializerAllOnOneLineOrOnePerLine: true
-ConstructorInitializerIndentWidth: 4
-ContinuationIndentWidth: 4
-Cpp11BracedListStyle: true
-DerivePointerAlignment: false
-DisableFormat: false
-ExperimentalAutoDetectBinPacking: false
-FixNamespaceComments: true
-ForEachMacros: [ foreach, Q_FOREACH, BOOST_FOREACH ]
-IncludeBlocks: Preserve
-IndentCaseLabels: false
-IndentPPDirectives: AfterHash
-IndentWidth: 4
-IndentWrappedFunctionNames: false
-KeepEmptyLinesAtTheStartOfBlocks: false
-MacroBlockBegin: ''
-MacroBlockEnd: ''
-MaxEmptyLinesToKeep: 1
-NamespaceIndentation: None
-PenaltyBreakAssignment: 2
-PenaltyBreakBeforeFirstCallParameter: 10000 # Raised intentionally; prefer breaking all
-PenaltyBreakComment: 300
-PenaltyBreakFirstLessLess: 120
-PenaltyBreakString: 1000
-PenaltyExcessCharacter: 1000000
-PenaltyReturnTypeOnItsOwnLine: 10000 # Raised intentionally because it hurts readability
-PointerAlignment: Left
-ReflowComments: true
-SortIncludes: Never
-SortUsingDeclarations: false
-SpaceAfterCStyleCast: true
-SpaceAfterTemplateKeyword: true
-SpaceBeforeAssignmentOperators: true
-SpaceBeforeCpp11BracedList: false
-SpaceBeforeInheritanceColon: true
-SpaceBeforeParens: ControlStatements
-SpaceBeforeCtorInitializerColon: true
-SpaceBeforeRangeBasedForLoopColon: true
-SpaceInEmptyParentheses: false
-SpacesBeforeTrailingComments: 2
-SpacesInAngles: false
-SpacesInCStyleCastParentheses: false
-SpacesInContainerLiterals: false
-SpacesInParentheses: false
-SpacesInSquareBrackets: false
-Standard: c++14
-TabWidth: 8
-UseTab: Never
-...
+SortIncludes: false
+ForEachMacros:
+ - FOREACH_IFACE
+ - FOREACH_PRIO
diff --git a/libcanard/.clang-tidy b/.clang-tidy
similarity index 66%
rename from libcanard/.clang-tidy
rename to .clang-tidy
index 910e2cbb..db7f329d 100644
--- a/libcanard/.clang-tidy
+++ b/.clang-tidy
@@ -19,10 +19,23 @@ Checks: >-
-bugprone-easily-swappable-parameters,
-llvm-header-guard,
-cert-dcl03-c,
+ -boost-use-ranges,
-hicpp-static-assert,
-misc-static-assert,
-*-macro-to-enum,
+ -*-macro-usage,
+ -*-enum-size,
+ -*-use-using,
+ -*-casting-through-void,
-misc-include-cleaner,
+ -cppcoreguidelines-avoid-do-while,
+ -*-magic-numbers,
+ -*-use-enum-class,
+ -*-use-trailing-return-type,
+ -*-deprecated-headers,
+ -*-avoid-c-arrays,
+ -*-nested-conditional-operator,
+ -*DeprecatedOrUnsafeBufferHandling,
CheckOptions:
- key: readability-function-cognitive-complexity.Threshold
value: '99'
diff --git a/.github/workflows/esp_dry_run.yml b/.github/workflows/esp_dry_run.yml
index 695e708e..a538e974 100644
--- a/.github/workflows/esp_dry_run.yml
+++ b/.github/workflows/esp_dry_run.yml
@@ -10,7 +10,7 @@ jobs:
upload_component:
runs-on: ubuntu-latest
steps:
- - uses: actions/checkout@v4
+ - uses: actions/checkout@v6
with:
submodules: "recursive"
diff --git a/.github/workflows/esp_publish.yml b/.github/workflows/esp_publish.yml
index 90b70160..ebd2aa65 100644
--- a/.github/workflows/esp_publish.yml
+++ b/.github/workflows/esp_publish.yml
@@ -10,7 +10,7 @@ jobs:
upload_component:
runs-on: ubuntu-latest
steps:
- - uses: actions/checkout@v4
+ - uses: actions/checkout@v6
with:
submodules: "recursive"
diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml
index bec68a8e..62202835 100644
--- a/.github/workflows/main.yml
+++ b/.github/workflows/main.yml
@@ -1,14 +1,14 @@
name: Verification & Static Analysis
on: [push, pull_request]
env:
- LLVM_VERSION: 19
+ LLVM_VERSION: 20
jobs:
debug:
if: github.event_name == 'push'
runs-on: ubuntu-latest
strategy:
matrix:
- toolchain: ['clang', 'gcc']
+ toolchain: ["clang", "gcc"]
include:
- toolchain: gcc
c-compiler: gcc
@@ -17,27 +17,33 @@ jobs:
c-compiler: clang
cxx-compiler: clang++
steps:
- - uses: actions/checkout@v4
+ - uses: actions/checkout@v6
+ with:
+ submodules: true
- run: |
wget https://apt.llvm.org/llvm.sh
chmod +x llvm.sh
sudo ./llvm.sh $LLVM_VERSION
sudo apt-get update -y && sudo apt-get upgrade -y
- sudo apt-get -y install gcc-multilib g++-multilib clang-tidy-$LLVM_VERSION
+ sudo apt-get -y install gcc-multilib g++-multilib clang-tidy-$LLVM_VERSION clang-format-$LLVM_VERSION cppcheck
sudo update-alternatives --install /usr/bin/clang-tidy clang-tidy /usr/bin/clang-tidy-$LLVM_VERSION 50
+ sudo update-alternatives --install /usr/bin/clang-format clang-format /usr/bin/clang-format-$LLVM_VERSION 50
+ sudo update-alternatives --set clang-tidy /usr/bin/clang-tidy-$LLVM_VERSION
+ sudo update-alternatives --set clang-format /usr/bin/clang-format-$LLVM_VERSION
clang-tidy --version
+ clang-format --version
- run: >
cmake
-B ${{ github.workspace }}/build
-DCMAKE_BUILD_TYPE=Debug
-DCMAKE_C_COMPILER=${{ matrix.c-compiler }}
-DCMAKE_CXX_COMPILER=${{ matrix.cxx-compiler }}
- tests
+ .
- working-directory: ${{github.workspace}}/build
run: |
make VERBOSE=1
make test
- - uses: actions/upload-artifact@v4
+ - uses: actions/upload-artifact@v7
if: always()
with:
name: ${{github.job}}-#${{strategy.job-index}}-${{job.status}}-${{join(matrix.*, ',')}}
@@ -50,7 +56,7 @@ jobs:
runs-on: ubuntu-latest
strategy:
matrix:
- toolchain: ['clang', 'gcc']
+ toolchain: ["clang", "gcc"]
build_type: [Release, MinSizeRel]
include:
- toolchain: gcc
@@ -60,7 +66,9 @@ jobs:
c-compiler: clang
cxx-compiler: clang++
steps:
- - uses: actions/checkout@v4
+ - uses: actions/checkout@v6
+ with:
+ submodules: true
- run: |
sudo apt-get update -y && sudo apt-get upgrade -y
sudo apt-get install gcc-multilib g++-multilib
@@ -71,12 +79,12 @@ jobs:
-DCMAKE_C_COMPILER=${{ matrix.c-compiler }}
-DCMAKE_CXX_COMPILER=${{ matrix.cxx-compiler }}
-DNO_STATIC_ANALYSIS=1
- tests
+ .
- working-directory: ${{github.workspace}}/build
run: |
make VERBOSE=1
make test
- - uses: actions/upload-artifact@v4
+ - uses: actions/upload-artifact@v7
if: always()
with:
name: ${{github.job}}-#${{strategy.job-index}}-${{job.status}}-${{join(matrix.*, ',')}}
@@ -84,125 +92,68 @@ jobs:
retention-days: 7
include-hidden-files: true
- avr:
+ coverage:
if: github.event_name == 'push'
runs-on: ubuntu-latest
- env:
- mcu: at90can64
- flags: -Wall -Wextra -Werror -pedantic -Wconversion -Wtype-limits
steps:
- - uses: actions/checkout@v4
+ - uses: actions/checkout@v6
+ with:
+ submodules: true
- run: |
sudo apt-get update -y && sudo apt-get upgrade -y
- sudo apt-get install gcc-avr avr-libc
- avr-gcc --version
- - run: avr-gcc libcanard/*.c -isystem lib/cavl2 -c -std=c99 -mmcu=${{ env.mcu }} ${{ env.flags }}
- - run: avr-gcc libcanard/*.c -isystem lib/cavl2 -c -std=c11 -mmcu=${{ env.mcu }} ${{ env.flags }}
- - run: avr-gcc libcanard/*.c -isystem lib/cavl2 -c -std=gnu99 -mmcu=${{ env.mcu }} ${{ env.flags }}
- - run: avr-gcc libcanard/*.c -isystem lib/cavl2 -c -std=gnu11 -mmcu=${{ env.mcu }} ${{ env.flags }}
+ sudo apt-get install -y gcc-multilib g++-multilib lcov
+ pip install --break-system-packages gcovr
+ - run: >
+ cmake
+ -B ${{ github.workspace }}/build
+ -DCMAKE_BUILD_TYPE=Debug
+ -DNO_STATIC_ANALYSIS=1
+ -DENABLE_COVERAGE=ON
+ .
+ - working-directory: ${{ github.workspace }}/build
+ run: |
+ make -j$(nproc)
+ make test
+ make coverage
+ # Export Cobertura report for Coveralls, tracking only libcanard/canard.c.
+ - run: |
+ cd "${{ github.workspace }}/build"
+ gcovr \
+ --root "${{ github.workspace }}" \
+ --filter '.*/libcanard/canard\.c$' \
+ --xml-pretty \
+ --output "${{ github.workspace }}/build/coverage-canard.cobertura.xml" \
+ --print-summary
+ - id: coveralls_upload
+ uses: coverallsapp/github-action@v2
+ continue-on-error: true
+ with:
+ github-token: ${{ secrets.GITHUB_TOKEN }}
+ file: build/coverage-canard.cobertura.xml
+ format: cobertura
+ - if: ${{ steps.coveralls_upload.outcome == 'failure' }}
+ run: |
+ echo "::warning::Coveralls upload failed (likely Coveralls API issue). Continuing without failing CI."
+ - uses: actions/upload-artifact@v7
+ if: always()
+ with:
+ name: ${{ github.job }}-coverage-report
+ path: ${{ github.workspace }}/build/coverage-html
+ retention-days: 30
arm:
if: github.event_name == 'push'
runs-on: ubuntu-latest
env:
- flags: -Wall -Wextra -Werror -pedantic -Wconversion -Wtype-limits -Wcast-align -Wfatal-errors
+ flags: >
+ -Wall -Wextra -Werror -pedantic -Wconversion -Wtype-limits -Wcast-align -Wfatal-errors
+ -Wno-error=unused-function
steps:
- - uses: actions/checkout@v4
+ - uses: actions/checkout@v6
+ with:
+ submodules: true
- run: |
sudo apt-get update -y && sudo apt-get upgrade -y
sudo apt-get install -y gcc-arm-none-eabi
- run: arm-none-eabi-gcc libcanard/*.c -isystem lib/cavl2 -c -std=c99 ${{ env.flags }}
- run: arm-none-eabi-gcc libcanard/*.c -isystem lib/cavl2 -c -std=c11 ${{ env.flags }}
-
- style_check:
- if: github.event_name == 'push'
- runs-on: ubuntu-latest
- steps:
- - uses: actions/checkout@v4
- - uses: DoozyX/clang-format-lint-action@v0.20
- with:
- source: './libcanard ./tests'
- exclude: './tests/catch'
- extensions: 'c,h,cpp,hpp'
- clangFormatVersion: ${{ env.LLVM_VERSION }}
-
- sonarcloud:
- if: >
- github.event_name == 'pull_request' ||
- contains(github.ref, '/master') ||
- contains(github.ref, '/release') ||
- contains(github.event.head_commit.message, '#sonar')
- runs-on: ubuntu-latest
- env:
- SONAR_SCANNER_VERSION: 5.0.1.3006
- SONAR_SERVER_URL: "https://sonarcloud.io"
- BUILD_WRAPPER_OUT_DIR: build_wrapper_output_directory
- GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
- SONAR_TOKEN: ${{ secrets.SONAR_TOKEN }}
- steps:
- - uses: actions/checkout@v4
- with:
- fetch-depth: 0
-
- - name: Install Dependencies
- run: |
- sudo apt-get update -y && sudo apt-get upgrade -y
- sudo apt-get install -y gcc-multilib g++-multilib
-
- - name: Set up JDK
- uses: actions/setup-java@v4
- with:
- java-version: 17
- distribution: zulu
-
- - name: Cache SonarCloud packages
- uses: actions/cache@v4
- with:
- path: ~/.sonar/cache
- key: ${{ runner.os }}-sonar
- restore-keys: ${{ runner.os }}-sonar
-
- - name: Download and set up sonar-scanner
- env:
- SONAR_SCANNER_DOWNLOAD_URL: https://binaries.sonarsource.com/Distribution/sonar-scanner-cli/sonar-scanner-cli-${{ env.SONAR_SCANNER_VERSION }}-linux.zip
- run: |
- mkdir -p $HOME/.sonar
- curl -sSLo $HOME/.sonar/sonar-scanner.zip ${{ env.SONAR_SCANNER_DOWNLOAD_URL }}
- unzip -o $HOME/.sonar/sonar-scanner.zip -d $HOME/.sonar/
- echo "$HOME/.sonar/sonar-scanner-${{ env.SONAR_SCANNER_VERSION }}-linux/bin" >> $GITHUB_PATH
-
- - name: Download and set up build-wrapper
- env:
- BUILD_WRAPPER_DOWNLOAD_URL: ${{ env.SONAR_SERVER_URL }}/static/cpp/build-wrapper-linux-x86.zip
- run: |
- curl -sSLo $HOME/.sonar/build-wrapper-linux-x86.zip ${{ env.BUILD_WRAPPER_DOWNLOAD_URL }}
- unzip -o $HOME/.sonar/build-wrapper-linux-x86.zip -d $HOME/.sonar/
- echo "$HOME/.sonar/build-wrapper-linux-x86" >> $GITHUB_PATH
-
- - name: Run build-wrapper
- run: |
- cmake tests -DCMAKE_BUILD_TYPE=Debug -DNO_STATIC_ANALYSIS=1 -DCMAKE_C_FLAGS='-DNDEBUG=1'
- build-wrapper-linux-x86-64 --out-dir ${{ env.BUILD_WRAPPER_OUT_DIR }} make all
- make test
- gcov --preserve-paths --long-file-names $(find CMakeFiles/test_private_cov.dir -name '*.gcno')
- gcov --preserve-paths --long-file-names $(find CMakeFiles/test_public_cov.dir -name '*.gcno')
-
- - name: Run sonar-scanner
- # Don't run sonar-scanner on builds originating from forks due to secrets not being available
- run: >
- [ -z "$SONAR_TOKEN" ] || sonar-scanner
- --define sonar.organization=opencyphal
- --define sonar.projectName=libcanard
- --define sonar.projectKey=libcanard
- --define sonar.sources=libcanard
- --define sonar.cfamily.gcov.reportsPath=.
- --define sonar.cfamily.compile-commands="${{ env.BUILD_WRAPPER_OUT_DIR }}/compile_commands.json"
- --define sonar.host.url="${{ env.SONAR_SERVER_URL }}"
-
- - uses: actions/upload-artifact@v4
- if: always()
- with:
- name: ${{github.job}}-#${{strategy.job-index}}-${{job.status}}-${{join(matrix.*, ',')}}
- path: ${{github.workspace}}/**/*
- retention-days: 7
- include-hidden-files: true
diff --git a/.gitignore b/.gitignore
index de4e1064..4de1c6bf 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,42 +1,27 @@
-# Object files
*.o
*.ko
*.obj
*.elf
-
-# Precompiled Headers
*.gch
*.pch
-
-# Libraries
*.lib
*.a
*.la
*.lo
-
-# Shared objects (inc. Windows DLLs)
*.dll
*.so
*.so.*
*.dylib
-
-# Executables
*.exe
*.out
*.app
*.i*86
*.x86_64
*.hex
-
-# Debug files
*.dSYM/
-
-# CMake build directory
-build/
+build*/
cmake-build-*/
-build-avr/
-
-# IDE and tools
+.cache*/
.metadata
.settings
.project
@@ -44,13 +29,11 @@ build-avr/
.pydevproject
.gdbinit
.vscode/
+.sisyphys/
**/.idea/*
!**/.idea/dictionaries
!**/.idea/dictionaries/*
-
-# Pycache
__pycache__/
-
-# OS stuff
.DS_Store
*.bak
+Testing/
diff --git a/.gitmodules b/.gitmodules
new file mode 100644
index 00000000..e061a133
--- /dev/null
+++ b/.gitmodules
@@ -0,0 +1,3 @@
+[submodule "lib/unity"]
+ path = lib/unity
+ url = https://github.com/ThrowTheSwitch/Unity
diff --git a/.idea/dictionaries/pavel.xml b/.idea/dictionaries/pavel.xml
deleted file mode 100644
index 18b66f09..00000000
--- a/.idea/dictionaries/pavel.xml
+++ /dev/null
@@ -1,93 +0,0 @@
-
-
-
- allocatee
- arithmetics
- backends
- baremetal
- bcast
- bootloaders
- bxcan
- cfamily
- coverity
- crtp
- cyphal
- dataflow
- dcanard
- ddtid
- deallocated
- deallocating
- deallocation
- deframing
- deinitializes
- demonstrational
- descatter
- discardment
- dnid
- dont
- dsdl
- dsonar
- dtid
- dtors
- errno
- gcov
- ieee
- iface
- ifnamsiz
- inak
- intravehicular
- irgdn
- izer
- kfrfx
- kirienko
- libcanard
- libuavcan
- memcpy
- microarchitecture
- microcontrollers
- misra
- msec
- multiframe
- nbytes
- noninfringement
- nosonar
- nutt
- opencyphal
- pdst
- permill
- pkut
- pointee
- prescaler
- prio
- pseudocode
- psrc
- pyuavcan
- qube
- roundtrip
- rtos
- rxstate
- serde
- signedness
- snid
- socketcan
- storages
- stringmakers
- submoduling
- subtreeing
- supremum
- transcompilers
- uavcan
- uint
- unicast
- untracked
- usec
- vendoring
- vssc
- wget
- xenial
- zubax
- zzzzz
- zzzzzz
-
-
-
\ No newline at end of file
diff --git a/.idea/dictionaries/project.xml b/.idea/dictionaries/project.xml
index ea1605a0..0d59a733 100644
--- a/.idea/dictionaries/project.xml
+++ b/.idea/dictionaries/project.xml
@@ -1,7 +1,30 @@
- candlc
+ Kirienko
+ Libcanard
+ acks
+ cyphal
+ dcanard
+ fdcan
+ frankentransfers
+ iface
+ ifaces
+ libcyphal
+ nolintbegin
+ nolintend
+ nosonar
+ objcount
+ popcount
+ seqno
+ seqnos
+ siocgifindex
+ splitmix
+ stdatomic
+ suppr
+ txfer
+ uavcan
+ unrespond
\ No newline at end of file
diff --git a/AGENTS.md b/AGENTS.md
new file mode 100644
index 00000000..07e2cd86
--- /dev/null
+++ b/AGENTS.md
@@ -0,0 +1,48 @@
+# LibCANard instructions for AI agents
+
+Read all README files in the project root and in all subdirectories except for `lib/`.
+
+The applicable specifications can be found here:
+- **Cyphal v1**: https://github.com/OpenCyphal/specification
+- **UAVCAN v0**, aka DroneCAN: https://dronecan.github.io/Specification/4.1_CAN_bus_transport_layer
+
+Project layout:
+
+- `libcanard`: the library itself; the shippable code.
+- `tests`: the test harness. Read its own README for details.
+- `lib`: external dependencies.
+
+## Style conventions
+
+Language targets: C99 for the library, C99 and C++20 for the test harness. Strict std only, compiler extensions not allowed.
+
+Naming patterns: `canard_*` functions, `canard_*_t` types, `CANARD_*` macros. Internal definitions need no prefixing. Enums and constants are `lower_snake_case`. Uppercase only for macros.
+
+Variables that are not mutated MUST be declared const, otherwise CI will reject the code.
+
+Keep code compact and add brief comments before non-obvious logic.
+
+Treat warnings as errors and keep compatibility with strict warning flags.
+
+**FORCE PUSH MUST NEVER BE USED**. The git history is sacrosanct and must not be rewritten. If you need to undo a change, make a new commit.
+
+For agent-authored commits, set `GIT_AUTHOR_NAME="Agent"` and `GIT_COMMITTER_NAME="Agent"`.
+
+The build system will reject code that is not clang-formatted; use build target `format` to invoke clang-format. This MUST be done before pushing code to avoid CI breakage.
+
+## Adversarial validation and verification
+
+Practice an adversarial approach to testing: the purpose of a test case is not to provide coverage, but to empirically prove correctness of the tested code. Always treat the code as suspect; you will be rewarded for pointing out flaws in it. If the code does not appear to be correct, refuse to test it and provide evidence of its defects instead of proceeding with testing.
+
+When using subagents to implement tests, always instruct them to summarize their findings concerning the correctness of the tested code and its possible limitations at the end of their run. At the end of the turn, provide a summary of the findings.
+
+To run tests with coverage measurement:
+
+```bash
+cmake -B build -DENABLE_COVERAGE=ON # Optionally, add -DNO_STATIC_ANALYSIS=ON
+cmake --build build -j$(nproc)
+cd build && ctest && make coverage
+xdg-open coverage-html/index.html
+```
+
+Coverage should focus on `canard.c` only. Coverage of other components is irrelevant.
diff --git a/CLAUDE.md b/CLAUDE.md
new file mode 120000
index 00000000..47dc3e3d
--- /dev/null
+++ b/CLAUDE.md
@@ -0,0 +1 @@
+AGENTS.md
\ No newline at end of file
diff --git a/CMakeLists.txt b/CMakeLists.txt
new file mode 100644
index 00000000..19519379
--- /dev/null
+++ b/CMakeLists.txt
@@ -0,0 +1,66 @@
+# This software is distributed under the terms of the MIT License.
+# Copyright (C) OpenCyphal Development Team
+# SPDX-License-Identifier: MIT
+# Author: Pavel Kirienko
+#
+# This file is only needed for library development and testing. It is not needed to use the library in your project;
+# instead, users should integrate the library by copying canard.c and canard.h.
+
+cmake_minimum_required(VERSION 3.20)
+
+project(canard)
+enable_testing()
+set(CMAKE_CTEST_ARGUMENTS "-V") # Enable test outputs when running `make test`
+set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
+
+# STATIC ANALYSIS
+option(NO_STATIC_ANALYSIS "Disable static analysis to speed up the build" OFF)
+if (NOT NO_STATIC_ANALYSIS)
+ # Clang-Tidy
+ find_program(clang_tidy NAMES clang-tidy REQUIRED)
+ message(STATUS "Using clang-tidy: ${clang_tidy}")
+ set(CMAKE_CXX_CLANG_TIDY ${clang_tidy})
+ set(CMAKE_C_CLANG_TIDY ${clang_tidy})
+
+ # Cppcheck
+ find_program(cppcheck NAMES cppcheck)
+ if (NOT cppcheck)
+ message(FATAL_ERROR "Could not locate cppcheck")
+ endif ()
+ message(STATUS "Using cppcheck: ${cppcheck}")
+ set(cppcheck_options
+ --enable=warning,style,performance,portability
+ --error-exitcode=2
+ --suppress=missingIncludeSystem
+ --suppress=badBitmaskCheck
+ --suppress=constParameterCallback
+ --suppress=duplInheritedMember
+ --suppress=preprocessorErrorDirective
+ --suppress=unreadVariable
+ --suppress=passedByValue
+ --suppress=containerOutOfBounds
+ --suppress=redundantAssignment
+ --inline-suppr
+ )
+ set(CMAKE_C_CPPCHECK ${cppcheck};--language=c;--std=c11;${cppcheck_options})
+ set(CMAKE_CXX_CPPCHECK ${cppcheck};--language=c++;--std=c++20;${cppcheck_options})
+
+ # Clang-Format
+ find_program(clang_format NAMES clang-format REQUIRED)
+ file(GLOB format_files
+ ${CMAKE_SOURCE_DIR}/libcanard/*.[ch]
+ ${CMAKE_SOURCE_DIR}/tests/*/*.[ch]
+ ${CMAKE_SOURCE_DIR}/tests/*/*.[ch]pp
+ )
+ message(STATUS "Using clang-format: ${clang_format}; files to format: ${format_files}")
+ add_custom_target(format COMMAND ${clang_format} -i -fallback-style=none -style=file --verbose ${format_files})
+ add_custom_target(
+ format_check
+ ALL
+ COMMAND ${clang_format} --dry-run --Werror -fallback-style=none -style=file --verbose ${format_files}
+ COMMENT "Checking clang-format conformance"
+ )
+endif ()
+
+add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/tests)
+add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/demos)
diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md
deleted file mode 100644
index 2dede3ce..00000000
--- a/CONTRIBUTING.md
+++ /dev/null
@@ -1,112 +0,0 @@
-# Libcanard contribution guide
-
-## Design principles
-
-The library is intended for use in real-time high-integrity applications.
-It is paramount that its temporal properties and resource utilization are plain to model and predict statically.
-The code shall follow applicable high-reliability coding guidelines as explained later in this document.
-The implementation shall be fully compliant with the Cyphal/CAN specification.
-
-The implementation and the API should be kept simple.
-There will be no high-level abstractions -- if that is desired, other implementations of Cyphal should be used.
-
-The library is intended for deeply embedded systems where the resources may be scarce.
-The ROM footprint is of a particular concern because the library should be usable with embedded bootloaders.
-
-## Directory layout
-
-The production sources and some minimal configuration files (such as `.clang-tidy`) are located under `/libcanard/`.
-Do not put anything else in there.
-
-The tests are located under `/tests/`.
-This directory also contains the top `CMakeLists.txt` needed to build and run the tests on the local machine.
-
-There is no separate storage for the documentation because it is written directly in the header files.
-This works for Libcanard because it is sufficiently compact and simple.
-
-## Standards
-
-The library shall be implemented in ISO C99/C11 following MISRA C:2012.
-The MISRA compliance is enforced by Clang-Tidy and SonarQube.
-Deviations are documented directly in the source code as follows:
-
-```c
-// Intentional violation of MISRA:
-<... deviant construct ...>
-```
-
-The full list of deviations with the accompanying explanation can be found by grepping the sources.
-
-Do not suppress compliance warnings using the means provided by static analysis tools because such deviations
-are impossible to track at the source code level.
-An exception applies for the case of false-positive (invalid) warnings -- those should not be mentioned in the codebase.
-
-[Zubax C++ Coding Conventions](https://kb.zubax.com/x/84Ah) shall be followed.
-Formatting is enforced by Clang-Format; it is used also to fail the CI/CD build if violations are detected.
-
-Unfortunately, some rules are hard or impractical to enforce automatically,
-so code reviewers shall be aware of MISRA and general high-reliability coding practices
-to prevent non-compliant code from being accepted into upstream.
-
-## Tools
-
-The following tools are required to conduct library development locally
-(check the CI workflow files for the required versions):
-
-- GCC
-- Clang and Clang-Tools
-- CMake
-- An AMD64 machine
-
-You may want to use the [toolshed](https://github.com/OpenCyphal/docker_toolchains/pkgs/container/toolshed)
-container for this.
-
-### Clang-Tidy
-
-Clang-Tidy is used to enforce compliance with MISRA and Zubax Coding Conventions.
-There are separate configuration files per directory:
-
-- `/libcanard/` (the production code) is equipped with the most stringent configuration.
-
-- `/tests/` is equipped with a separate configuration which omits certain rules that are considered
- expensive to maintain.
- This is because the test suite is intentionally kept to a somewhat lower quality bar to reduce development costs.
-
-Clang-Tidy is invoked automatically on each translation unit before it is compiled;
-the build will fail if the tool is not available locally.
-To disable this behavior, pass `NO_STATIC_ANALYSIS=1` to CMake at the generation time.
-
-### Clang-Format
-
-Clang-Format is used to enforce compliance with MISRA and Zubax Coding Conventions.
-There is a single configuration file at the root of the repository.
-
-To reformat the sources, generate the project and build the target `format`; e.g., for Make: `make format`.
-
-### SonarQube
-
-SonarQube is a cloud solution so its use is delegated to the CI/CD pipeline.
-If you need access, please get in touch with the OpenCyphal Development Team members.
-
-### IDE
-
-The recommended development environment is JetBrains CLion. The root project file is `tests/CMakeLists.txt`.
-The repository contains the spelling dictionaries for CLion located under `.idea/`, make sure to use them.
-
-## Testing
-
-Generate the CMake project, build all, and then build the target `test` (e.g., `make test`).
-The tests are built for x86 and x86_64; the latter is why an AMD64 machine is required for local development.
-
-At the moment, the library is not being tested against other platforms.
-We would welcome contributions implementing CI/CD testing against popular embedded architectures, particularly
-the ARM Cortex M series and AVR in an emulator.
-As a high-integrity library, the Libcanard test suite should provide full test coverage for all commonly used platforms.
-
-**WARNING:**
-[Catch2 is NOT thread-safe!](https://github.com/catchorg/Catch2/blob/1e379de9d7522b294e201700dcbb36d4f8037301/docs/limitations.md#thread-safe-assertions)
-Never use `REQUIRE` etc. anywhere but the main thread.
-
-## Releasing
-
-Simply create a new release on GitHub:
diff --git a/MIGRATION_v3.x_to_v4.0.md b/MIGRATION_v3.x_to_v4.0.md
deleted file mode 100644
index ba12eb00..00000000
--- a/MIGRATION_v3.x_to_v4.0.md
+++ /dev/null
@@ -1,331 +0,0 @@
-# Migration Guide: Updating from Libcanard v3.x to v4.0
-
-This guide is intended to help developers migrate their applications from Libcanard version 3.x to version 4.0. It outlines the key changes between the two versions and provides step-by-step instructions to update your code accordingly.
-
-## Introduction
-
-Libcanard is a compact implementation of the Cyphal/CAN protocol designed for high-integrity real-time embedded systems. Version 4 introduces several changes that may impact your existing codebase. This guide will help you understand these changes and update your application accordingly.
-
-These changes do not affect wire compatibility.
-
-## Version Changes
-
-- **Libcanard Version**:
- - **Old**: `CANARD_VERSION_MAJOR 3`
- - **New**: `CANARD_VERSION_MAJOR 4`
-- **Cyphal Specification Version**: Remains the same (`1.0`).
-
-## API Changes
-
-### New Functions
-
-- **`canardTxFree`**:
- - **Description**: A helper function to free memory allocated for transmission queue items, including the frame payload buffer.
- - **Prototype**:
- ```c
- void canardTxFree(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- struct CanardTxQueueItem* const item);
- ```
- - **Usage**: After popping a transmission queue item using `canardTxPop`, use `canardTxFree` to deallocate its memory.
-
-- **`canardTxPoll`**:
- - **Description**: A helper function simplifies the transmission process by combining frame retrieval, transmission, and cleanup into a single function.
- - **Prototype**:
- ```c
- int8_t canardTxPoll(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond now_usec,
- void* const user_reference,
- const CanardTxFrameHandler frame_handler,
- uint64_t* const frames_expired,
- uint64_t* const frames_failed);
- ```
- - **Purpose**: Streamlines the process of handling frames from the TX queue.
- - **Functionality**:
- - Retrieves the next frame to be transmitted.
- - Invokes a user-provided `frame_handler` to transmit the frame.
- - Manages frame cleanup based on the handler's return value.
- - Automatically drops timed-out frames if `now_usec` is provided.
- - Increments the statistical counters `frames_expired` and `frames_failed` unless their pointers are NULL.
-
-### Modified Functions
-
-Several functions have updated prototypes and usage patterns:
-
-1. **`canardInit`**:
- - **Old Prototype**:
- ```c
- CanardInstance canardInit(const CanardMemoryAllocate memory_allocate,
- const CanardMemoryFree memory_free);
- ```
- - **New Prototype**:
- ```c
- struct CanardInstance canardInit(const struct CanardMemoryResource memory);
- ```
- - **Changes**:
- - Replaces `CanardMemoryAllocate` and `CanardMemoryFree` function pointers with a `CanardMemoryResource` struct.
-
-1. **`canardTxInit`**:
- - **Old Prototype**:
- ```c
- CanardTxQueue canardTxInit(const size_t capacity,
- const size_t mtu_bytes);
- ```
- - **New Prototype**:
- ```c
- struct CanardTxQueue canardTxInit(const size_t capacity,
- const size_t mtu_bytes,
- const struct CanardMemoryResource memory);
- ```
- - **Changes**:
- - Adds a `CanardMemoryResource` parameter for memory allocation of payload data.
-
-1. **`canardTxPush`**:
- - **Old Prototype**:
- ```c
- int32_t canardTxPush(CanardTxQueue* const que,
- CanardInstance* const ins,
- const CanardMicrosecond tx_deadline_usec,
- const CanardTransferMetadata* const metadata,
- const size_t payload_size,
- const void* const payload);
- ```
- - **New Prototype**:
- ```c
- int32_t canardTxPush(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond tx_deadline_usec,
- const struct CanardTransferMetadata* const metadata,
- const struct CanardPayload payload,
- const CanardMicrosecond now_usec,
- uint64_t* const frames_expired);
- ```
- - **Changes**:
- - Replaces `payload_size` and `payload` with a single `CanardPayload` struct.
- - Adds a `now_usec` parameter for handling timed-out frames.
- - **Purpose**: Allows the library to automatically drop frames that have exceeded their transmission deadlines (`tx_deadline_usec`).
- - **Behavior**: If `now_usec` is greater than `tx_deadline_usec`, the frames already in the TX queue will be dropped, and the `frames_expired` counter will be incremented.
- - **Optional Feature**: Passing `0` for `now_usec` disables automatic dropping, maintaining previous behavior.
- - Adds a new `frames_expired` parameter that is incremented for every expired frame, unless NULL.
-
-1. **`canardTxPeek`** and **`canardTxPop`**:
- - The functions now return and accept pointers to mutable `struct CanardTxQueueItem` instead of const pointers.
-
-### Removed Functions
-
-- No functions have been explicitly removed, but some have modified prototypes.
-
-## Data Structure Changes
-
-### Type Definitions
-
-- **Enumerations**:
- - Changed from `typedef enum` to `enum` without `typedef`.
- - **Old**:
- ```c
- typedef enum { ... } CanardPriority;
- ```
- - **New**:
- ```c
- enum CanardPriority { ... };
- ```
-
-- **Structures**:
- - Changed from forward declarations and `typedef struct` to direct `struct` definitions.
- - **Old**:
- ```c
- typedef struct CanardInstance CanardInstance;
- ```
- - **New**:
- ```c
- struct CanardInstance { ... };
- ```
-
-- **Function pointers**:
- - **Added** `CanardTxFrameHandler` function pointer type.
- ```c
- typedef int8_t (*CanardTxFrameHandler)(void* const user_reference,
- const CanardMicrosecond deadline_usec,
- struct CanardMutableFrame* const frame);
- ```
-
-### Struct Modifications
-
-- **`CanardFrame`**:
- - **Old**:
- ```c
- typedef struct {
- uint32_t extended_can_id;
- size_t payload_size;
- const void* payload;
- } CanardFrame;
- ```
- - **New**:
- ```c
- struct CanardFrame {
- uint32_t extended_can_id;
- struct CanardPayload payload;
- };
- ```
- - **Changes**:
- - Payload now uses the `CanardPayload` struct.
-
-- **New Structs Introduced**:
- - **`CanardPayload`** and **`CanardMutablePayload`**: Encapsulate payload data and size.
- - **`CanardMutableFrame`**: Similar to `CanardFrame` but uses `CanardMutablePayload`.
-
-- **`CanardInstance`**:
- - Now contains a `CanardMemoryResource` for memory management instead of separate function pointers.
-
-- **`CanardTxQueue`**:
- - Includes a `CanardMemoryResource` for payload data allocation.
-
-- **`CanardMemoryResource`** and **`CanardMemoryDeleter`**:
- - New structs to encapsulate memory allocation and deallocation functions along with user references.
-
-## Memory Management Changes
-
-- **Memory Resource Structs**:
- - Memory allocation and deallocation are now handled via `CanardMemoryResource` and `CanardMemoryDeleter` structs.
- - Functions now receive these structs instead of direct function pointers.
-
-- **Allocation Functions**:
- - **Allocation**:
- ```c
- typedef void* (*CanardMemoryAllocate)(void* const user_reference, const size_t size);
- ```
- - **Deallocation**:
- ```c
- typedef void (*CanardMemoryDeallocate)(void* const user_reference, const size_t size, void* const pointer);
- ```
-
-## Automatic Dropping of Timed-Out Frames
-
-#### Description
-
-Frames in the TX queue that have exceeded their `tx_deadline_usec` can now be automatically dropped when `now_usec` is provided to `canardTxPush()` or `canardTxPoll()`.
-
-- **Benefit**: Reduces the worst-case peak memory footprint.
-- **Optional**: Feature can be disabled by passing `0` for `now_usec`.
-
-#### Migration Steps
-
-1. **Enable or Disable Automatic Dropping**:
-
- - **Enable**: Provide the current time to `now_usec` in both `canardTxPush()` and `canardTxPoll()`.
- - **Disable**: Pass `0` to `now_usec` to retain manual control.
-
-2. **Adjust Application Logic**:
-
- - Monitor the statistical counters if tracking of dropped frames is required.
-
-## Migration Steps
-
-1. **Update Type Definitions**:
- - Replace all `typedef`-based enum and struct types with direct `struct` and `enum` declarations.
- - For example, change `CanardInstance` to `struct CanardInstance`.
-
-1. **Adjust Memory Management Code**:
- - Replace separate memory allocation and deallocation function pointers with `CanardMemoryResource` and `CanardMemoryDeleter` structs.
- - Update function calls and definitions accordingly.
-
-1. **Modify Function Calls**:
- - Update all function calls to match the new prototypes.
- - **`canardInit`**:
- - Before:
- ```c
- canardInit(memory_allocate, memory_free);
- ```
- - After:
- ```c
- struct CanardMemoryResource memory = {
- .user_reference = ...,
- .allocate = memory_allocate,
- .deallocate = memory_free
- };
- canardInit(memory);
- ```
- - **`canardTxInit`**:
- - Before:
- ```c
- canardTxInit(capacity, mtu_bytes);
- ```
- - After:
- ```c
- canardTxInit(capacity, mtu_bytes, memory);
- ```
- - **`canardTxPush`**:
- - Before:
- ```c
- canardTxPush(que, ins, tx_deadline_usec, metadata, payload_size, payload);
- ```
- - After:
- ```c
- struct CanardPayload payload_struct = {
- .size = payload_size,
- .data = payload
- };
- uint64_t frames_expired = 0; // This is optional; pass NULL if not needed.
- canardTxPush(que, ins, tx_deadline_usec, metadata, payload_struct, now_usec, &frames_expired);
- ```
-
-1. **Handle New Functions**:
- - Use `canardTxFree` to deallocate transmission queue items after popping them.
- - Example:
- ```c
- struct CanardTxQueueItem* item = canardTxPeek(&tx_queue);
- while (item != NULL) {
- // Transmit the frame...
- canardTxPop(&tx_queue, item);
- canardTxFree(&tx_queue, &canard_instance, item);
- item = canardTxPeek(&tx_queue);
- }
- ```
-
- - If currently using `canardTxPeek()`, `canardTxPop()`, and `canardTxFree()`, consider replacing that logic with `canardTxPoll()` for simplicity.
- - Define a function matching the `CanardTxFrameHandler` signature:
- ```c
- int8_t myFrameHandler(void* const user_reference,
- const CanardMicrosecond deadline_usec,
- struct CanardMutableFrame* frame)
- {
- // Implement transmission logic here
- // Return positive value on success - the frame will be released
- // Return zero to retry later - the frame will stay in the TX queue
- // Return negative value on failure - whole transfer (including this frame) will be dropped
- }
- ```
- - Example:
- ```c
- // Before
- struct CanardTxQueueItem* item = canardTxPeek(queue);
- if (item != NULL) {
- // Handle deadline
- // Transmit item->frame
- // Unless the media is busy:
- item = canardTxPop(queue, item);
- canardTxFree(queue, instance, item);
- }
- // After
- uint64_t frames_expired = 0; // The counters are optional; pass NULL if not needed.
- uint64_t frames_failed = 0;
- int8_t result = canardTxPoll(queue,
- instance,
- now_usec,
- user_reference,
- myFrameHandler,
- &frames_expired,
- &frames_failed);
- ```
-1. **Update Struct Field Access**:
- - Adjust your code to access struct fields directly, considering the changes in struct definitions.
- - For example, access `payload.size` instead of `payload_size`.
-
-1. **Adjust Memory Allocation Logic**:
- - Ensure that your memory allocation and deallocation functions conform to the new prototypes.
- - Pay attention to the additional `size` parameter in the deallocation function.
-
-1. **Test Thoroughly**:
- - After making the changes, thoroughly test your application to ensure that it functions correctly with the new library version.
- - Pay special attention to memory management and potential leaks.
diff --git a/README.md b/README.md
index 38182f87..3c3ee7b0 100644
--- a/README.md
+++ b/README.md
@@ -2,11 +2,8 @@
# Cyphal/CAN transport in C
-[](https://github.com/OpenCyphal/libcanard/actions/workflows/main.yml)
-[](https://sonarcloud.io/dashboard?id=libcanard)
-[](https://sonarcloud.io/dashboard?id=libcanard)
-[](https://sonarcloud.io/dashboard?id=libcanard)
-[](https://sonarcloud.io/dashboard?id=libcanard)
+[](https://github.com/OpenCyphal/libcanard/actions/workflows/main.yml)
+[](https://coveralls.io/github/OpenCyphal/libcanard)
[](https://forum.opencyphal.org)
@@ -14,239 +11,153 @@
-----
Libcanard is a robust implementation of the Cyphal/CAN transport layer in C for high-integrity real-time embedded systems.
+Supports Cyphal v1.1, v1.0, and legacy UAVCAN v0 aka DroneCAN.
-[Cyphal](https://opencyphal.org) is an open lightweight data bus standard designed for reliable intravehicular
-communication in aerospace and robotic applications via CAN bus, Ethernet, and other robust transports.
-
-**Read the docs in [`libcanard/canard.h`](/libcanard/canard.h).**
-
-Find examples, starters, tutorials on the
-[Cyphal forum](https://forum.opencyphal.org/t/libcanard-examples-starters-tutorials/935).
-
-If you want to contribute, please read [`CONTRIBUTING.md`](/CONTRIBUTING.md).
+The library supports both Classic CAN and CAN FD, in redundant and non-redundant configurations.
-## Features
-
-- Full test coverage and extensive static analysis.
-- Compliance with automatically enforceable MISRA C rules (reach out to for details).
-- Detailed time complexity and memory requirement models for the benefit of real-time high-integrity applications.
-- Purely reactive API without the need for background servicing.
-- Support for the Classic CAN and CAN FD.
-- Support for redundant network interfaces.
-- Compatibility with 8/16/32/64-bit platforms.
-- Compatibility with extremely resource-constrained baremetal environments starting from 32K ROM and 32K RAM.
-- Implemented in ≈1000 SLoC.
-
-## Platforms
-
-The library is designed to be usable out of the box with any conventional 8/16/32/64-bit platform,
-including deeply embedded baremetal platforms, as long as there is a standard-compliant compiler available.
-The platform-specific media IO layer (driver) is supposed to be provided by the application:
-
- +---------------------------------+
- | Application |
- +-------+-----------------+-------+
- | |
- +-------+-------+ +-------+-------+
- | Libcanard | | CAN driver |
- +---------------+ +-------+-------+
- |
- +-------+-------+
- | CAN controller|
- +---------------+
+The library is compatible with 8/16/32/64-bit platforms, including extremely resource-constrained
+baremetal MCU platforms starting from 32K ROM and 32K RAM.
+The interface with the underlying platform is very clean and minimal, enabling quick adaptation to any CAN-enabled MCU.
The OpenCyphal Development Team maintains a collection of various platform-specific components in a separate repository
at .
Users are encouraged to search through that repository for drivers, examples, and other pieces that may be
reused in the target application to speed up the design of the media IO layer (driver) for the application.
-## Example
-
-The example augments the documentation but does not replace it.
-
-The library requires a constant-complexity deterministic dynamic memory allocator.
-We could use the standard C heap, but most implementations are not constant-complexity,
-so let's suppose that we're using [O1Heap](https://github.com/pavel-kirienko/o1heap) instead.
-We are going to need basic wrappers:
+[Cyphal](https://opencyphal.org) is an open lightweight data bus standard designed for reliable intravehicular
+communication in aerospace and robotic applications via CAN bus, Ethernet, and other robust transports.
-```c
-static void* memAllocate(void* const user_reference, const size_t size)
+**Read the docs in [`libcanard/canard.h`](libcanard/canard.h).**
+
+## Quick start
+
+📚 Find runnable examples under `demos/`.
+
+```c++
+#include
+#include
+#include "canard.h"
+
+// Return the current monotonic time in microseconds starting from some arbitrary instant in the past (e.g., boot).
+static canard_us_t app_now(const canard_t* const self);
+
+// Embedded systems may prefer https://github.com/pavel-kirienko/o1heap.
+static void* app_alloc(const canard_mem_t memory, const size_t size) { return malloc(size); }
+static void app_free(const canard_mem_t memory, const size_t size, void* const pointer) { free(pointer); }
+
+// Transmit a CAN frame non-blockingly; return true if submitted, false if would block (will try again later).
+// Frame transmission may be aborted if it doesn't hit the bus before the deadline.
+static bool app_tx(canard_t* const self,
+ void* const user_context,
+ const canard_us_t deadline,
+ const uint_least8_t iface_index,
+ const bool fd,
+ const uint32_t extended_can_id,
+ const canard_bytes_t can_data);
+
+// Process a received message. The user may attach arbitrary context to the subscription via the user context pointer.
+static void app_on_message(canard_subscription_t* const self,
+ const canard_us_t timestamp,
+ const canard_prio_t priority,
+ const uint_least8_t source_node_id,
+ const uint_least8_t transfer_id,
+ const canard_payload_t payload)
{
- (void) user_reference;
- return o1heapAllocate(my_allocator, size);
+ // payload.view contains the useful payload bytes.
+ if (payload.origin.data != NULL) { // The application may keep the payload if necessary; eventually must release.
+ free(payload.origin.data);
+ }
}
-static void memFree(void* const user_reference, const size_t size, void* const pointer)
+int main(void)
{
- (void) user_reference;
- (void) size;
- o1heapFree(my_allocator, pointer);
-}
-```
-
-Init a library instance:
+ static const canard_mem_vtable_t mem_vtable = { .free = app_free, .alloc = app_alloc };
+ const canard_mem_t mem = { .vtable = &mem_vtable, .context = NULL };
+ const canard_mem_set_t mem_set = { .tx_transfer = mem, .tx_frame = mem, .rx_session = mem, .rx_payload = mem };
+ const canard_vtable_t vtable = { .now = app_now, .tx = app_tx };
+ static const canard_subscription_vtable_t sub_vtable = { .on_message = app_on_message };
+
+ // Set up the local node. The node-ID will be allocated automatically.
+ canard_t node;
+ if (!canard_new(&node, &vtable, mem_set, 100, UID_OR_TRUE_RANDOM_NUMBER, 0U)) {
+ return -1;
+ }
+ if (!canard_set_node_id(&node, 42U)) {
+ canard_destroy(&node);
+ return -1;
+ }
+
+ // Subscribe for messages.
+ canard_subscription_t sub;
+ if (!canard_subscribe_13b(&node, &sub, 7509U, 63U, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_us, &sub_vtable)) {
+ canard_destroy(&node);
+ return -1;
+ }
-```c
-const struct CanardMemoryResource memory = {NULL, memFree, memAllocate};
-struct CanardInstance canard = canardInit(memory);
-canard.node_id = 42; // Defaults to anonymous; can be set up later at any point.
+ // Publish a message.
+ const canard_bytes_chain_t payload = { .bytes = {.size = 12, .data = "Hello world!"} };
+ assert(canard_publish_13b(&node,
+ app_now(&node) + 1000000,
+ CANARD_IFACE_BITMAP_ALL,
+ canard_prio_nominal,
+ 7509U,
+ 0U,
+ payload,
+ NULL));
+
+ canard_poll(&node, CANARD_IFACE_BITMAP_ALL); // Call again whenever one or more ifaces become writable.
+
+ // Later, when a CAN frame is received:
+ // static const uint8_t rx_frame_bytes[8] = { ... };
+ // (void)canard_ingest_frame(&node,
+ // app_now(&node),
+ // 0U,
+ // rx_extended_can_id,
+ // (canard_bytes_t){.size = sizeof(rx_frame_bytes), .data = rx_frame_bytes});
+
+ canard_unsubscribe(&node, &sub);
+ canard_destroy(&node);
+ return 0;
+}
```
-In order to be able to send transfers over the network, we will need one transmission queue per redundant CAN interface:
+## Revisions
-```c
-const struct CanardMemoryResource tx_memory = {NULL, memFree, memAllocate};
-struct CanardTxQueue queue = canardTxInit(
- 100, // Limit the size of the queue at 100 frames.
- CANARD_MTU_CAN_FD, // Set MTU = 64 bytes. There is also CANARD_MTU_CAN_CLASSIC.
- tx_memory);
-```
+To release a new version, simply publish a new release on GitHub.
-Publish a message (message serialization not shown):
-
-```c
-static uint8_t my_message_transfer_id; // Must be static or heap-allocated to retain state between calls.
-const struct CanardTransferMetadata transfer_metadata = {
- .priority = CanardPriorityNominal,
- .transfer_kind = CanardTransferKindMessage,
- .port_id = 1234, // This is the subject-ID.
- .remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
- .transfer_id = my_message_transfer_id,
-};
-++my_message_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
-int32_t result = canardTxPush(&queue, // Call this once per redundant CAN interface (queue).
- &canard,
- tx_deadline_usec, // Transmission deadline (absolute monotonic time in usec).
- &transfer_metadata,
- 47, // Size of the message payload (see Nunavut transpiler).
- "\x2D\x00" "Sancho, it strikes me thou art in great fear.",
- NULL);
-if (result < 0)
-{
- // An error has occurred: either an argument is invalid, the TX queue is full, or we've run out of memory.
- // It is possible to statically prove that an out-of-memory will never occur for a given application if the
- // heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
-}
-```
+### v5.0 [WORK IN PROGRESS]
-Use [Nunavut](https://github.com/OpenCyphal/nunavut) to automatically generate
-(de)serialization code from DSDL definitions.
+v5 is a major rework based on the experience gained from extensive production use of the previous revisions.
+The API has been redesigned from scratch and as such there is no migration guide available;
+please read the new `canard.h` to see how to use the library -- the new API is simpler than the old one.
-The CAN frames generated from the message transfer are now stored in the `queue`.
-We need to pick them out one by one and have them transmitted.
-Normally, the following fragment should be invoked periodically to unload the CAN frames from the
-prioritized transmission queue (or several, if redundant network interfaces are used) into the CAN driver:
+Main changes:
-```c
-for (struct CanardTxQueueItem* ti = NULL; (ti = canardTxPeek(&queue)) != NULL;) // Peek at the top of the queue.
-{
- if ((0U == ti->tx_deadline_usec) || (ti->tx_deadline_usec > getCurrentMicroseconds())) // Check the deadline.
- {
- if (!pleaseTransmit(ti)) // Send the frame over this redundant CAN iface.
- {
- break; // If the driver is busy, break and retry later.
- }
- }
- // After the frame is transmitted or if it has timed out while waiting, pop it from the queue and deallocate:
- canardTxFree(&queue, &canard, canardTxPop(&queue, ti));
-}
-```
+- Support for new protocols alongside Cyphal v1.0:
+ - Cyphal/CAN v1.1, which adds support for 16-bit subject-IDs (like in UAVCAN v0) via a new CAN ID layout format.
+ - UAVCAN v0 aka DroneCAN, a legacy predecessor to Cyphal v1.0 that is still widely used.
-💡 New in v4.0: optionally, you can now use `canardTxPoll()` that automates the above for you.
-
-Transfer reception is done by feeding frames into the transfer reassembly state machine
-from any of the redundant interfaces.
-But first, we need to subscribe:
-
-```c
-struct CanardRxSubscription heartbeat_subscription;
-(void) canardRxSubscribe(&canard, // Subscribe to messages uavcan.node.Heartbeat.
- CanardTransferKindMessage,
- 7509, // The fixed Subject-ID of the Heartbeat message type (see DSDL definition).
- 16, // The extent (the maximum possible payload size) provided by Nunavut.
- CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
- &heartbeat_subscription);
-
-struct CanardRxSubscription my_service_subscription;
-(void) canardRxSubscribe(&canard, // Subscribe to an arbitrary service response.
- CanardTransferKindResponse, // Specify that we want service responses, not requests.
- 123, // The Service-ID whose responses we will receive.
- 1024, // The extent (see above).
- CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
- &my_service_subscription);
-```
+- Anonymous messages can no longer be transmitted, but they can still be received.
-The "extent" refers to the minimum amount of memory required to hold any serialized representation of any compatible
-version of the data type; or, in other words, it is the maximum possible size of received objects.
-This parameter is determined by the data type author at the data type definition time.
-It is typically larger than the maximum object size in order to allow the data type author to introduce more
-fields in the future versions of the type;
-for example, `MyMessage.1.0` may have the maximum size of 100 bytes and the extent 200 bytes;
-a revised version `MyMessage.1.1` may have the maximum size anywhere between 0 and 200 bytes.
-Extent values are provided per data type by DSDL transcompilers such as Nunavut.
-
-In Libcanard we use the term "subscription" not only for subjects (messages), but also for RPC services.
-
-We can subscribe and unsubscribe at runtime as many times as we want.
-Normally, however, an embedded application would subscribe once and roll with it.
-Okay, this is how we receive transfers:
-
-```c
-struct CanardRxTransfer transfer;
-const int8_t result = canardRxAccept(&canard,
- rx_timestamp_usec, // When the frame was received, in microseconds.
- &received_frame, // The CAN frame received from the bus.
- redundant_interface_index, // If the transport is not redundant, use 0.
- &transfer,
- NULL);
-if (result < 0)
-{
- // An error has occurred: either an argument is invalid or we've ran out of memory.
- // It is possible to statically prove that an out-of-memory will never occur for a given application if
- // the heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
- // Reception of an invalid frame is NOT an error.
-}
-else if (result == 1)
-{
- processReceivedTransfer(redundant_interface_index, &transfer); // A transfer has been received, process it.
- canard.memory_free(&canard, transfer.payload); // Deallocate the dynamic memory afterwards.
-}
-else
-{
- // Nothing to do.
- // The received frame is either invalid or it's a non-last frame of a multi-frame transfer.
- // Reception of an invalid frame is NOT reported as an error because it is not an error.
-}
-```
+- A new passive node-ID autoconfiguration based on a simple occupancy observer.
+ This method is decentralized and is compatible with old nodes.
+ A node-ID can still be assigned manually if needed.
-A simple API for generating CAN hardware acceptance filter configurations is also provided.
-Acceptance filters are generated in an extended 29-bit ID + mask scheme and can be used to minimize
-the number of irrelevant transfers processed in software.
-
-```c
-// Generate an acceptance filter to receive only uavcan.node.Heartbeat.1.0 messages (fixed port-ID 7509):
-struct CanardFilter heartbeat_config = canardMakeFilterForSubject(7509);
-// And to receive only uavcan.register.Access.1.0 service transfers (fixed port-ID 384):
-struct CanardFilter register_access_config = canardMakeFilterForService(384, ins.node_id);
-
-// You can also combine the two filter configurations into one (may also accept irrelevant messages).
-// This allows consolidating a large set of configurations to fit the number of hardware filters.
-// For more information on the optimal subset of configurations to consolidate to minimize wasted CPU,
-// see the Cyphal specification.
-struct CanardFilter combined_config =
- canardConsolidateFilters(&heartbeat_config, ®ister_access_config);
-configureHardwareFilters(combined_config.extended_can_id, combined_config.extended_mask);
-```
+- Automatic CAN acceptance filter configuration based on the current subscription set.
+ The configuration is refreshed whenever the subscription set is modified or the local node-ID is changed.
-Full API specification is available in the documentation.
-If you find the examples to be unclear or incorrect, please, open a ticket.
+- New TX pipeline using per-transfer queue granularity with efficient CAN frame deduplication across redundant
+ interfaces, which resulted in a major reduction of heap memory footprint (typ. x2+ reduction).
-## Revisions
+- New RX pipeline supporting priority level preemption without transfer loss and reduced memory consumption.
+ The old revision was susceptible to transfer loss when the remote initiated a higher-priority multi-frame
+ transfer while a lower-priority multi-frame transfer was in flight. The v5 revision maintains concurrent
+ reassemblers per priority level, enabling arbitrary priority nesting.
### v4.0
Updating from Libcanard v3 to v4 involves several changes in memory management and TX frame expiration.
-Please follow the [MIGRATION_v3.x_to_v4.0](MIGRATION_v3.x_to_v4.0.md) guide and carefully update your code.
+Please follow the `MIGRATION_v3.x_to_v4.0.md` guide available in the v4 codebase.
### v3.2
diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt
new file mode 100644
index 00000000..b30ab52c
--- /dev/null
+++ b/demos/CMakeLists.txt
@@ -0,0 +1,20 @@
+# This software is distributed under the terms of the MIT License.
+# Copyright (c) OpenCyphal.
+# Author: Pavel Kirienko
+
+cmake_minimum_required(VERSION 3.12)
+
+add_executable(heartbeat_monitor heartbeat_monitor.c ${CMAKE_SOURCE_DIR}/libcanard/canard.c)
+target_include_directories(heartbeat_monitor PRIVATE ${CMAKE_SOURCE_DIR}/libcanard)
+target_include_directories(heartbeat_monitor SYSTEM PRIVATE ${CMAKE_SOURCE_DIR}/lib/cavl2)
+set_target_properties(
+ heartbeat_monitor
+ PROPERTIES
+ C_STANDARD 99
+ C_EXTENSIONS OFF
+ COMPILE_FLAGS "-Wall -Wextra -Werror -pedantic -Wconversion -Wsign-conversion -Wno-unused-function"
+ C_CLANG_TIDY ""
+ C_CPPCHECK ""
+ CXX_CLANG_TIDY ""
+ CXX_CPPCHECK ""
+)
diff --git a/demos/heartbeat_monitor.c b/demos/heartbeat_monitor.c
new file mode 100644
index 00000000..1c6bd65a
--- /dev/null
+++ b/demos/heartbeat_monitor.c
@@ -0,0 +1,372 @@
+// This software is distributed under the terms of the MIT License.
+// Copyright (c) OpenCyphal.
+// Author: Pavel Kirienko
+//
+// Minimal heartbeat monitor demo using GNU/Linux SocketCAN.
+// Subscribes to Cyphal v1 heartbeats (subject 7509) and DroneCAN NodeStatus (DTID 341) simultaneously,
+// and prints a refreshing table of all detected nodes with their uptime.
+//
+// Usage: heartbeat_monitor
+//
+// Quick test with virtual CAN:
+// sudo modprobe vcan && sudo ip link add vcan0 type vcan && sudo ip link set up vcan0
+// ./heartbeat_monitor vcan0
+
+#define _DEFAULT_SOURCE // For clock_gettime, struct timespec, etc.
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#define CYPHAL_HEARTBEAT_SUBJECT_ID 7509U
+#define CYPHAL_HEARTBEAT_EXTENT 7U
+#define DRONECAN_NODE_STATUS_DTID 341U
+#define DRONECAN_NODE_STATUS_SIGNATURE 0x0F0868D0C1A7C6F1ULL
+#define DRONECAN_NODE_STATUS_EXTENT 7U
+#define NODE_OFFLINE_TIMEOUT_US 5000000LL // 5 seconds
+
+// ---------------------------------------- Node table ----------------------------------------
+
+typedef struct
+{
+ uint32_t uptime;
+ int64_t last_seen_us;
+ uint_least8_t health;
+ uint_least8_t mode;
+ bool seen;
+} node_entry_t;
+
+enum
+{
+ PROTO_CYPHAL = 0,
+ PROTO_DRONECAN = 1,
+ PROTO_COUNT = 2,
+};
+
+static node_entry_t g_nodes[PROTO_COUNT][CANARD_NODE_ID_MAX + 1U];
+
+static const char* const g_cyphal_health_str[] = { "NOMINAL", "ADVISORY", "CAUTION", "WARNING" };
+static const char* const g_dronecan_health_str[] = { "OK", "WARNING", "ERROR", "CRITICAL" };
+static const char* const g_mode_str[] = {
+ [0] = "OPERATIONAL", [1] = "INITIALIZATION", [2] = "MAINTENANCE", [3] = "SOFTWARE_UPDATE", [7] = "OFFLINE",
+};
+static const char* const g_proto_str[] = { "Cyphal", "DroneCAN" };
+
+// ---------------------------------------- Platform ----------------------------------------
+
+static int64_t get_monotonic_us(void)
+{
+ struct timespec ts;
+ (void)clock_gettime(CLOCK_MONOTONIC, &ts);
+ return (int64_t)ts.tv_sec * 1000000LL + (int64_t)ts.tv_nsec / 1000LL;
+}
+
+static void mem_free(const canard_mem_t mem, const size_t size, void* const ptr)
+{
+ (void)mem;
+ (void)size;
+ free(ptr);
+}
+static void* mem_alloc(const canard_mem_t mem, const size_t size)
+{
+ (void)mem;
+ return malloc(size);
+}
+static const canard_mem_vtable_t g_mem_vtable = { .free = mem_free, .alloc = mem_alloc };
+
+// ---------------------------------------- Canard vtable ----------------------------------------
+
+static canard_us_t vtable_now(const canard_t* const self)
+{
+ (void)self;
+ return get_monotonic_us();
+}
+static bool vtable_tx(canard_t* const self,
+ void* const user_context,
+ const canard_us_t deadline,
+ const uint_least8_t iface_index,
+ const bool fd,
+ const uint32_t extended_can_id,
+ const canard_bytes_t can_data)
+{
+ (void)self;
+ (void)user_context;
+ (void)deadline;
+ (void)iface_index;
+ (void)fd;
+ (void)extended_can_id;
+ (void)can_data;
+ return false; // Receive-only demo.
+}
+static const canard_vtable_t g_canard_vtable = { .now = vtable_now, .tx = vtable_tx, .filter = NULL };
+
+// ---------------------------------------- Subscription callbacks ----------------------------------------
+
+static uint32_t read_u32_le(const void* const data)
+{
+ const uint8_t* const d = (const uint8_t*)data;
+ return (uint32_t)d[0] | ((uint32_t)d[1] << 8U) | ((uint32_t)d[2] << 16U) | ((uint32_t)d[3] << 24U);
+}
+
+static void update_node(const int proto,
+ const uint_least8_t node_id,
+ const uint32_t uptime,
+ const uint8_t health,
+ const uint8_t mode)
+{
+ node_entry_t* const n = &g_nodes[proto][node_id];
+ n->uptime = uptime;
+ n->health = health;
+ n->mode = mode;
+ n->last_seen_us = get_monotonic_us();
+ n->seen = true;
+}
+
+static void release_payload(const canard_payload_t payload)
+{
+ if (payload.origin.data != NULL) {
+ free(payload.origin.data);
+ }
+}
+
+static void decode_cyphal_heartbeat(const uint_least8_t node_id, const canard_payload_t payload)
+{
+ if ((node_id <= CANARD_NODE_ID_MAX) && (payload.view.size >= CYPHAL_HEARTBEAT_EXTENT)) {
+ const uint8_t* const d = (const uint8_t*)payload.view.data;
+ update_node(PROTO_CYPHAL, node_id, read_u32_le(d), d[4] & 0x03U, d[5] & 0x07U);
+ }
+ release_payload(payload);
+}
+
+static void decode_dronecan_node_status(const uint_least8_t node_id, const canard_payload_t payload)
+{
+ if ((node_id <= CANARD_NODE_ID_MAX) && (payload.view.size >= DRONECAN_NODE_STATUS_EXTENT)) {
+ const uint8_t* const d = (const uint8_t*)payload.view.data;
+ const uint8_t status = d[4];
+ update_node(PROTO_DRONECAN, node_id, read_u32_le(d), status & 0x03U, (status >> 2U) & 0x07U);
+ }
+ release_payload(payload);
+}
+
+static void on_cyphal_heartbeat(canard_subscription_t* const self,
+ const canard_us_t timestamp,
+ const canard_prio_t priority,
+ const uint_least8_t source_node_id,
+ const uint_least8_t transfer_id,
+ const canard_payload_t payload)
+{
+ (void)self;
+ (void)timestamp;
+ (void)priority;
+ (void)transfer_id;
+ decode_cyphal_heartbeat(source_node_id, payload);
+}
+
+static void on_dronecan_heartbeat(canard_subscription_t* const self,
+ const canard_us_t timestamp,
+ const canard_prio_t priority,
+ const uint_least8_t source_node_id,
+ const uint_least8_t transfer_id,
+ const canard_payload_t payload)
+{
+ (void)self;
+ (void)timestamp;
+ (void)priority;
+ (void)transfer_id;
+ decode_dronecan_node_status(source_node_id, payload);
+}
+
+static const canard_subscription_vtable_t g_sub_vtable_cyphal = { .on_message = on_cyphal_heartbeat };
+static const canard_subscription_vtable_t g_sub_vtable_dronecan = { .on_message = on_dronecan_heartbeat };
+
+// ---------------------------------------- Display ----------------------------------------
+
+static void print_table(const char* const iface_name)
+{
+ const int64_t now = get_monotonic_us();
+ // Move cursor home and clear screen.
+ (void)fputs("\033[H\033[2J", stdout);
+ (void)printf("Heartbeat Monitor - %s\n\n", iface_name);
+ (void)puts("Protocol | Node | Uptime | Health | Mode");
+ (void)puts("---------+------+----------+----------+----------------");
+ size_t count = 0;
+ for (int proto = 0; proto < PROTO_COUNT; proto++) {
+ for (size_t nid = 0; nid <= CANARD_NODE_ID_MAX; nid++) {
+ const node_entry_t* const n = &g_nodes[proto][nid];
+ if (n->seen && ((now - n->last_seen_us) < NODE_OFFLINE_TIMEOUT_US)) {
+ const char* const* const health_table =
+ (proto == PROTO_CYPHAL) ? g_cyphal_health_str : g_dronecan_health_str;
+ const char* const health = (n->health < 4U) ? health_table[n->health] : "?";
+ const char* const mode = (n->mode < 8U) && (g_mode_str[n->mode] != NULL) ? g_mode_str[n->mode] : "?";
+ (void)printf("%-8s | %4zu | %8us | %-8s | %s\n", g_proto_str[proto], nid, n->uptime, health, mode);
+ count++;
+ }
+ }
+ }
+ if (count == 0) {
+ (void)puts(" (no nodes detected)");
+ }
+ (void)printf("\n%zu node%s online\n", count, (count == 1) ? "" : "s");
+ (void)fflush(stdout);
+}
+
+// ---------------------------------------- SocketCAN ----------------------------------------
+
+static int open_can_socket(const char* const iface_name)
+{
+ const int fd = socket(AF_CAN, SOCK_RAW, CAN_RAW);
+ if (fd < 0) {
+ perror("socket");
+ return -1;
+ }
+ const int enable_can_fd = 1;
+ if (setsockopt(fd, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &enable_can_fd, sizeof(enable_can_fd)) < 0) {
+ perror("setsockopt(CAN_RAW_FD_FRAMES)");
+ (void)close(fd);
+ return -1;
+ }
+ struct ifreq ifr;
+ (void)memset(&ifr, 0, sizeof(ifr));
+ (void)strncpy(ifr.ifr_name, iface_name, sizeof(ifr.ifr_name) - 1U);
+ if (ioctl(fd, SIOCGIFINDEX, &ifr) < 0) {
+ perror("ioctl(SIOCGIFINDEX)");
+ (void)close(fd);
+ return -1;
+ }
+ struct sockaddr_can addr;
+ (void)memset(&addr, 0, sizeof(addr));
+ addr.can_family = AF_CAN;
+ addr.can_ifindex = ifr.ifr_ifindex;
+ if (bind(fd, (struct sockaddr*)&addr, sizeof(addr)) < 0) {
+ perror("bind");
+ (void)close(fd);
+ return -1;
+ }
+ return fd;
+}
+
+// ---------------------------------------- Main ----------------------------------------
+
+static volatile sig_atomic_t g_running = 1;
+static void on_sigint(const int sig)
+{
+ (void)sig;
+ g_running = 0;
+}
+
+static void print_usage(const char* const program_name)
+{
+ (void)fprintf(stderr, "Usage: %s \n", program_name);
+}
+
+int main(const int argc, const char* const argv[])
+{
+ if (argc != 2) {
+ print_usage(argv[0]);
+ return 1;
+ }
+ const char* const iface_name = argv[1];
+
+ // Open SocketCAN.
+ const int sock = open_can_socket(iface_name);
+ if (sock < 0) {
+ return 1;
+ }
+
+ // Initialize canard.
+ const canard_mem_t mem = { .vtable = &g_mem_vtable, .context = NULL };
+ canard_t ins;
+ if (!canard_new(&ins,
+ &g_canard_vtable,
+ (canard_mem_set_t){
+ .tx_transfer = mem,
+ .tx_frame = mem,
+ .rx_session = mem,
+ .rx_payload = mem,
+ .rx_filters = mem,
+ },
+ 0, // tx_queue_capacity: receive-only
+ 0, // prng_seed: irrelevant for receive-only
+ 0)) // filter_count: no HW filters
+ {
+ (void)fputs("canard_new failed\n", stderr);
+ (void)close(sock);
+ return 1;
+ }
+
+ // Subscribe to Cyphal heartbeat (subject 7509, 13-bit subject-ID space).
+ canard_subscription_t sub_cyphal;
+ if (!canard_subscribe_13b(&ins,
+ &sub_cyphal,
+ CYPHAL_HEARTBEAT_SUBJECT_ID,
+ CYPHAL_HEARTBEAT_EXTENT,
+ CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_us,
+ &g_sub_vtable_cyphal)) {
+ (void)fputs("canard_subscribe_13b failed\n", stderr);
+ canard_destroy(&ins);
+ (void)close(sock);
+ return 1;
+ }
+
+ // Subscribe to DroneCAN NodeStatus (DTID 341).
+ canard_subscription_t sub_dronecan;
+ const uint16_t dronecan_crc_seed = canard_v0_crc_seed_from_data_type_signature(DRONECAN_NODE_STATUS_SIGNATURE);
+ if (!canard_v0_subscribe(&ins,
+ &sub_dronecan,
+ DRONECAN_NODE_STATUS_DTID,
+ dronecan_crc_seed,
+ DRONECAN_NODE_STATUS_EXTENT,
+ CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_us,
+ &g_sub_vtable_dronecan)) {
+ (void)fputs("canard_v0_subscribe failed\n", stderr);
+ canard_unsubscribe(&ins, &sub_cyphal);
+ canard_destroy(&ins);
+ (void)close(sock);
+ return 1;
+ }
+
+ (void)signal(SIGINT, on_sigint);
+ (void)signal(SIGTERM, on_sigint);
+ (void)printf("Listening on %s... (Ctrl+C to exit)\n", iface_name);
+
+ int64_t last_display_us = 0;
+ while (g_running) {
+ struct pollfd pfd = { .fd = sock, .events = POLLIN, .revents = 0 };
+ const int pr = poll(&pfd, 1, 100); // 100 ms timeout
+ if (pr > 0 && (pfd.revents & POLLIN)) {
+ struct canfd_frame frame;
+ const ssize_t nbytes = read(sock, &frame, sizeof(frame));
+ if ((nbytes == CAN_MTU) || (nbytes == CANFD_MTU)) {
+ // Only process extended data frames (both Cyphal and DroneCAN use 29-bit IDs).
+ if ((frame.can_id & CAN_EFF_FLAG) && !(frame.can_id & (CAN_RTR_FLAG | CAN_ERR_FLAG))) {
+ const canard_bytes_t data = { .size = frame.len, .data = frame.data };
+ (void)canard_ingest_frame(&ins, get_monotonic_us(), 0, frame.can_id & CAN_EFF_MASK, data);
+ }
+ }
+ }
+ canard_poll(&ins, 0);
+
+ // Refresh the display approximately once per second.
+ const int64_t now = get_monotonic_us();
+ if ((now - last_display_us) >= 1000000LL) {
+ last_display_us = now;
+ print_table(iface_name);
+ }
+ }
+
+ (void)fputs("\nShutting down.\n", stdout);
+ canard_unsubscribe(&ins, &sub_dronecan);
+ canard_unsubscribe(&ins, &sub_cyphal);
+ canard_destroy(&ins);
+ (void)close(sock);
+ return 0;
+}
diff --git a/lib/cavl2/cavl2.h b/lib/cavl2/cavl2.h
index cf540137..1b83eaf3 100644
--- a/lib/cavl2/cavl2.h
+++ b/lib/cavl2/cavl2.h
@@ -135,8 +135,44 @@ static inline CAVL2_T* cavl2_find(CAVL2_T* root, const void* const user_comparat
/// If the node is not in the tree, the behavior is undefined; it may create cycles in the tree which is deadly.
/// It is safe to pass the result of cavl2_find/cavl2_find_or_insert directly as the second argument:
/// cavl2_remove(&root, cavl2_find(&root, user, search_comparator));
-/// It is recommended to invalidate the pointers stored in the node after its removal.
-static inline void cavl2_remove(CAVL2_T** const root, const CAVL2_T* const node);
+/// The removed node will have all of its pointers set to NULL.
+static inline void cavl2_remove(CAVL2_T** const root, CAVL2_T* const node);
+
+/// Replace the specified node with another node without rebalancing.
+/// This is useful when you want to replace a node with an equivalent one (same key ordering).
+/// The new node takes over the position (parent, children, balance factor) of the old node.
+/// The old node will have all of its pointers set to NULL.
+/// The new node must not already be in the tree; if it is, the behavior is undefined.
+/// The new node's fields (up, lr, bf) will be overwritten to match the old node's position in the tree.
+/// The complexity is O(1).
+/// The function has no effect if any of the pointers are NULL.
+/// If the old node is not in the tree, the behavior is undefined.
+static inline void cavl2_replace(CAVL2_T** const root, CAVL2_T* const old_node, CAVL2_T* const new_node);
+
+/// True iff the node is in the tree. The complexity is O(1).
+/// Returns false if the node is NULL.
+/// Assumes that the node pointers are NULL when it is not inserted (this is ensured by the removal function).
+static inline bool cavl2_is_inserted(const CAVL2_T* const root, const CAVL2_T* const node)
+{
+ bool out = false;
+ if (node != NULL) {
+ out = (node->up != NULL) || (node->lr[0] != NULL) || (node->lr[1] != NULL) || (node == root);
+ }
+ return out;
+}
+
+/// Remove the specified node if it is inserted in the tree; otherwise, do nothing.
+/// This is a convenience wrapper that combines cavl2_is_inserted() and cavl2_remove().
+/// Returns true if the node was inserted and has been removed, false otherwise.
+static inline bool cavl2_remove_if(CAVL2_T** const root, CAVL2_T* const node)
+{
+ bool removed = false;
+ if ((root != NULL) && cavl2_is_inserted(*root, node)) {
+ cavl2_remove(root, node);
+ removed = true;
+ }
+ return removed;
+}
/// Return the min-/max-valued node stored in the tree, depending on the flag. This is an extremely fast query.
/// Returns NULL iff the argument is NULL (i.e., the tree is empty). The worst-case complexity is O(log n).
@@ -183,6 +219,98 @@ static inline CAVL2_T* cavl2_next_greater(CAVL2_T* const node)
return c;
}
+/// Find and return the root of the tree given an arbitrary node.
+/// Returns NULL if the argument is NULL. The worst-case complexity is O(log n).
+static inline CAVL2_T* cavl2_root(CAVL2_T* node)
+{
+ if (node != NULL) {
+ while (node->up != NULL) {
+ node = node->up;
+ }
+ }
+ return node;
+}
+
+/// Find the smallest node whose value is greater than or equal to the search target, in O(log n).
+/// Returns the first node for which the comparator returns a non-positive result.
+/// If no such node exists (all nodes compare less than target), returns NULL.
+/// The comparator returns: positive if target>candidate, zero if target==candidate, negative if target 5; target=5 => 5; target=8 => NULL.
+static inline CAVL2_T* cavl2_lower_bound(CAVL2_T* const root,
+ const void* const user,
+ const cavl2_comparator_t comparator)
+{
+ CAVL2_T* result = NULL;
+ if ((root != NULL) && (comparator != NULL)) {
+ CAVL2_T* n = root;
+ while (n != NULL) {
+ const CAVL2_RELATION cmp = comparator(user, n);
+ if (cmp <= 0) {
+ result = n;
+ n = n->lr[0];
+ } else {
+ n = n->lr[1];
+ }
+ }
+ }
+ return result;
+}
+
+/// Find the smallest node whose value is strictly greater than the search target (upper bound).
+/// Returns the first node for which the comparator returns a negative result.
+/// See cavl2_lower_bound() for details.
+/// Example: tree={1,3,5,7}, target=4 => 5; target=5 => 7; target=7 => NULL.
+static inline CAVL2_T* cavl2_upper_bound(CAVL2_T* const root,
+ const void* const user,
+ const cavl2_comparator_t comparator)
+{
+ CAVL2_T* result = NULL;
+ if ((root != NULL) && (comparator != NULL)) {
+ CAVL2_T* n = root;
+ while (n != NULL) {
+ const CAVL2_RELATION cmp = comparator(user, n);
+ if (cmp < 0) {
+ result = n;
+ n = n->lr[0];
+ } else {
+ n = n->lr[1];
+ }
+ }
+ }
+ return result;
+}
+
+/// Find the largest node whose value is less than or equal to the search target, in O(log n).
+/// Returns the last node for which the comparator returns a non-negative result.
+/// See cavl2_lower_bound() for details.
+/// Example: tree={1,3,5,7}, target=4 => 3; target=5 => 5; target=0 => NULL.
+static inline CAVL2_T* cavl2_predecessor(CAVL2_T* const root,
+ const void* const user,
+ const cavl2_comparator_t comparator)
+{
+ CAVL2_T* result = NULL;
+ if ((root != NULL) && (comparator != NULL)) {
+ CAVL2_T* n = root;
+ while (n != NULL) {
+ const CAVL2_RELATION cmp = comparator(user, n);
+ if (cmp >= 0) {
+ result = n;
+ n = n->lr[1];
+ } else {
+ n = n->lr[0];
+ }
+ }
+ }
+ return result;
+}
+
+/// The successor counterpart of cavl2_predecessor() is an alias of cavl2_lower_bound(), provided for completeness only.
+/// Example: tree={1,3,5,7}, target=4 => 5; target=5 => 5; target=8 => NULL.
+static inline CAVL2_T* cavl2_successor(CAVL2_T* const root, const void* const user, const cavl2_comparator_t comparator)
+{
+ return cavl2_lower_bound(root, user, comparator);
+}
+
/// The trivial factory is useful in most applications. It simply returns the user pointed converted to CAVL2_T.
/// It is meant for use with cavl2_find_or_insert().
static inline CAVL2_T* cavl2_trivial_factory(void* const user)
@@ -207,18 +335,20 @@ static inline CAVL2_T* cavl2_trivial_factory(void* const user)
/// struct cavl2_t* tree_node_b = cavl2_find(...); // whatever
/// if (tree_node_b == NULL) { ... } // do something else
/// struct my_type_t* my_struct = CAVL2_TO_OWNER(tree_node_b, struct my_type_t, tree_b);
-///
-/// The result is undefined if the tree_node_ptr is not a valid pointer to the tree node.
-#define CAVL2_TO_OWNER(tree_node_ptr, owner_type, owner_tree_node_field) \
- (((tree_node_ptr) == NULL) \
- ? NULL \
- : ((owner_type*)(void*)(((char*)(tree_node_ptr)) - offsetof(owner_type, owner_tree_node_field)))) // NOLINT
+#define CAVL2_TO_OWNER(tree_node_ptr, owner_type, owner_tree_node_field) \
+ ((owner_type*)cavl2_impl_to_owner_helper((tree_node_ptr), offsetof(owner_type, owner_tree_node_field))) // NOLINT
// ---------------------------------------- END OF PUBLIC API SECTION ----------------------------------------
// ---------------------------------------- POLICE LINE DO NOT CROSS ----------------------------------------
+/// INTERNAL USE ONLY.
+static inline void* cavl2_impl_to_owner_helper(const void* const tree_node_ptr, const size_t offset)
+{
+ return (tree_node_ptr == NULL) ? NULL : (void*)((char*)tree_node_ptr - offset);
+}
+
/// INTERNAL USE ONLY. Makes the '!r' child of node 'x' its parent; i.e., rotates 'x' toward 'r'.
-static inline void _cavl2_rotate(CAVL2_T* const x, const bool r)
+static inline void cavl2_impl_rotate(CAVL2_T* const x, const bool r)
{
CAVL2_ASSERT((x != NULL) && (x->lr[!r] != NULL) && ((x->bf >= -1) && (x->bf <= +1)));
CAVL2_T* const z = x->lr[!r];
@@ -237,7 +367,7 @@ static inline void _cavl2_rotate(CAVL2_T* const x, const bool r)
/// INTERNAL USE ONLY.
/// Accepts a node and how its balance factor needs to be changed -- either +1 or -1.
/// Returns the new node to replace the old one if tree rotation took place, same node otherwise.
-static inline CAVL2_T* _cavl2_adjust_balance(CAVL2_T* const x, const bool increment)
+static inline CAVL2_T* cavl2_impl_adjust_balance(CAVL2_T* const x, const bool increment)
{
CAVL2_ASSERT((x != NULL) && ((x->bf >= -1) && (x->bf <= +1)));
CAVL2_T* out = x;
@@ -249,7 +379,7 @@ static inline CAVL2_T* _cavl2_adjust_balance(CAVL2_T* const x, const bool increm
CAVL2_ASSERT(z != NULL); // Heavy side cannot be empty. NOLINTNEXTLINE(clang-analyzer-core.NullDereference)
if ((z->bf * sign) <= 0) { // Parent and child are heavy on the same side or the child is balanced.
out = z;
- _cavl2_rotate(x, r);
+ cavl2_impl_rotate(x, r);
if (0 == z->bf) {
x->bf = (int_fast8_t)(-sign);
z->bf = (int_fast8_t)(+sign);
@@ -261,8 +391,8 @@ static inline CAVL2_T* _cavl2_adjust_balance(CAVL2_T* const x, const bool increm
CAVL2_T* const y = z->lr[r];
CAVL2_ASSERT(y != NULL); // Heavy side cannot be empty.
out = y;
- _cavl2_rotate(z, !r);
- _cavl2_rotate(x, r);
+ cavl2_impl_rotate(z, !r);
+ cavl2_impl_rotate(x, r);
if ((y->bf * sign) < 0) {
x->bf = (int_fast8_t)(+sign);
y->bf = 0;
@@ -285,7 +415,7 @@ static inline CAVL2_T* _cavl2_adjust_balance(CAVL2_T* const x, const bool increm
/// INTERNAL USE ONLY.
/// Takes the culprit node (the one that is added); returns NULL or the root of the tree (possibly new one).
/// When adding a new node, set its balance factor to zero and call this function to propagate the changes upward.
-static inline CAVL2_T* _cavl2_retrace_on_growth(CAVL2_T* const added)
+static inline CAVL2_T* cavl2_impl_retrace_on_growth(CAVL2_T* const added)
{
CAVL2_ASSERT((added != NULL) && (0 == added->bf));
CAVL2_T* c = added; // Child
@@ -293,11 +423,10 @@ static inline CAVL2_T* _cavl2_retrace_on_growth(CAVL2_T* const added)
while (p != NULL) {
const bool r = p->lr[1] == c; // c is the right child of parent
CAVL2_ASSERT(p->lr[r] == c);
- c = _cavl2_adjust_balance(p, r);
+ c = cavl2_impl_adjust_balance(p, r);
p = c->up;
- if (0 ==
- c->bf) { // The height change of the subtree made this parent perfectly balanced (as all things should be),
- break; // hence, the height of the outer subtree is unchanged, so upper balance factors are unchanged.
+ if (0 == c->bf) { // The height change of the subtree made this parent balanced (as all things should be),
+ break; // hence, the height of the outer subtree is unchanged, so upper balance factors are unchanged.
}
}
CAVL2_ASSERT(c != NULL);
@@ -332,7 +461,7 @@ static inline CAVL2_T* cavl2_find_or_insert(CAVL2_T** const root,
out->lr[1] = NULL;
out->up = up;
out->bf = 0;
- CAVL2_T* const rt = _cavl2_retrace_on_growth(out);
+ CAVL2_T* const rt = cavl2_impl_retrace_on_growth(out);
if (rt != NULL) {
*root = rt;
}
@@ -342,7 +471,7 @@ static inline CAVL2_T* cavl2_find_or_insert(CAVL2_T** const root,
return out;
}
-static inline void cavl2_remove(CAVL2_T** const root, const CAVL2_T* const node)
+static inline void cavl2_remove(CAVL2_T** const root, CAVL2_T* const node)
{
if ((root != NULL) && (node != NULL)) {
CAVL2_ASSERT(*root != NULL); // Otherwise, the node would have to be NULL.
@@ -367,8 +496,7 @@ static inline void cavl2_remove(CAVL2_T** const root, const CAVL2_T* const node)
re->lr[1] = node->lr[1];
re->lr[1]->up = re;
r = false;
- } else // In this case, we are reducing the height of the right subtree, so r=1.
- {
+ } else { // In this case, we are reducing the height of the right subtree, so r=1.
p = re; // Retracing starts with the replacement node itself as we are deleting its parent.
r = true; // The right child of the replacement node remains the same so we don't bother relinking it.
}
@@ -401,7 +529,7 @@ static inline void cavl2_remove(CAVL2_T** const root, const CAVL2_T* const node)
if (p != NULL) {
CAVL2_T* c = NULL;
for (;;) {
- c = _cavl2_adjust_balance(p, !r);
+ c = cavl2_impl_adjust_balance(p, !r);
p = c->up;
if ((c->bf != 0) || (NULL == p)) { // Reached the root or the height difference is absorbed by c.
break;
@@ -413,6 +541,41 @@ static inline void cavl2_remove(CAVL2_T** const root, const CAVL2_T* const node)
*root = c;
}
}
+ // Invalidate the node's pointers to indicate it is no longer in the tree.
+ node->up = NULL;
+ node->lr[0] = NULL;
+ node->lr[1] = NULL;
+ }
+}
+
+static inline void cavl2_replace(CAVL2_T** const root, CAVL2_T* const old_node, CAVL2_T* const new_node)
+{
+ if ((root != NULL) && (old_node != NULL) && (new_node != NULL)) {
+ CAVL2_ASSERT(*root != NULL); // Otherwise, old_node would have to be NULL.
+ CAVL2_ASSERT((old_node->up != NULL) || (old_node == *root)); // old_node must be in the tree.
+ CAVL2_ASSERT((new_node->up == NULL) && (new_node->lr[0] == NULL) && (new_node->lr[1] == NULL));
+ // Copy the structural data from the old node to the new node.
+ new_node->up = old_node->up;
+ new_node->lr[0] = old_node->lr[0];
+ new_node->lr[1] = old_node->lr[1];
+ new_node->bf = old_node->bf;
+ // Update the parent to point to the new node.
+ if (old_node->up != NULL) {
+ old_node->up->lr[old_node->up->lr[1] == old_node] = new_node;
+ } else {
+ *root = new_node;
+ }
+ // Update the children to point to the new parent.
+ if (old_node->lr[0] != NULL) {
+ old_node->lr[0]->up = new_node;
+ }
+ if (old_node->lr[1] != NULL) {
+ old_node->lr[1]->up = new_node;
+ }
+ // Invalidate the old node's pointers to indicate it is no longer in the tree.
+ old_node->up = NULL;
+ old_node->lr[0] = NULL;
+ old_node->lr[1] = NULL;
}
}
diff --git a/lib/unity b/lib/unity
new file mode 160000
index 00000000..51d2db98
--- /dev/null
+++ b/lib/unity
@@ -0,0 +1 @@
+Subproject commit 51d2db98e292545321fcf23999920622b5bcf772
diff --git a/libcanard/canard.c b/libcanard/canard.c
index 5a555bc5..276014c7 100644
--- a/libcanard/canard.c
+++ b/libcanard/canard.c
@@ -1,87 +1,173 @@
-/// This software is distributed under the terms of the MIT License.
-/// Copyright (c) OpenCyphal.
-/// Author: Pavel Kirienko
+// This software is distributed under the terms of the MIT License.
+// Copyright (c) OpenCyphal.
+// Author: Pavel Kirienko
+// Contributors: https://github.com/OpenCyphal/libcanard/contributors
#include "canard.h"
+#include
+#include
#include
#include
+#if __STDC_VERSION__ >= 202311L
+#include
+#endif
-// --------------------------------------------- BUILD CONFIGURATION ---------------------------------------------
-
-/// Define this macro to include build configuration header.
-/// Usage example with CMake: "-DCANARD_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/my_canard_config.h\""
+// Define this macro to include build configuration header.
+// Usage example with CMake: "-DCANARD_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/my_canard_config.h\""
#ifdef CANARD_CONFIG_HEADER
-# include CANARD_CONFIG_HEADER
+#include CANARD_CONFIG_HEADER // cppcheck suppress "preprocessorErrorDirective"
#endif
-/// By default, this macro resolves to the standard assert(). The user can redefine this if necessary.
-/// To disable assertion checks completely, make it expand into `(void)(0)`.
+// By default, this macro resolves to the standard assert().
+// To disable assertion checks completely, make it expand into `(void)(0)`.
#ifndef CANARD_ASSERT
-// Intentional violation of MISRA: inclusion not at the top of the file to eliminate unnecessary dependency on assert.h.
-# include // NOSONAR
// Intentional violation of MISRA: assertion macro cannot be replaced with a function definition.
-# define CANARD_ASSERT(x) assert(x) // NOSONAR
-#endif
-
-/// Define CANARD_CRC_TABLE=0 to use slow but ROM-efficient transfer-CRC computation algorithm.
-/// Doing so is expected to save ca. 500 bytes of ROM and increase the cost of RX/TX transfer processing by ~half.
-#ifndef CANARD_CRC_TABLE
-# define CANARD_CRC_TABLE 1
+#define CANARD_ASSERT(x) assert(x) // NOSONAR
#endif
-/// This macro is needed for testing and for library development.
-#ifndef CANARD_PRIVATE
-# define CANARD_PRIVATE static inline
+#if __STDC_VERSION__ < 201112L
+// Intentional violation of MISRA: static assertion macro cannot be replaced with a function definition.
+#define static_assert(x, ...) typedef char _static_assert_gl(_static_assertion_, __LINE__)[(x) ? 1 : -1] // NOSONAR
+#define _static_assert_gl(a, b) _static_assert_gl_impl(a, b) // NOSONAR
+// Intentional violation of MISRA: the paste operator ## cannot be avoided in this context.
+#define _static_assert_gl_impl(a, b) a##b // NOSONAR
#endif
#if !defined(__STDC_VERSION__) || (__STDC_VERSION__ < 199901L)
-# error "Unsupported language: ISO C99 or a newer version is required."
+#error "Unsupported language: ISO C99 or a newer version is required."
#endif
-// --------------------------------------------- INTERNAL INCLUDES ----------------------------------------------
// The internal includes are placed here after the config header is included and CANARD_ASSERT is defined.
-#define CAVL2_T struct CanardTreeNode
-#define CAVL2_ASSERT(x) CANARD_ASSERT(x) // NOSONAR
+#define CAVL2_T canard_tree_t
+#define CAVL2_RELATION int32_t
+#define CAVL2_ASSERT(x) CANARD_ASSERT(x) // NOSONAR
#include
-// --------------------------------------------- COMMON DEFINITIONS ---------------------------------------------
+typedef unsigned char byte_t;
-#define BITS_PER_BYTE 8U
-#define BYTE_MAX 0xFFU
+#define BYTE_MAX 0xFFU
+#define BIG_BANG INT64_MIN
+#define CAN_EXT_ID_MASK ((UINT32_C(1) << 29U) - 1U)
+#define PADDING_BYTE_VALUE 0U
+#define PRIO_SHIFT 26U
-#define CAN_EXT_ID_MASK ((UINT32_C(1) << 29U) - 1U)
+#define TAIL_SOT 128U
+#define TAIL_EOT 64U
+#define TAIL_TOGGLE 32U
-#define MFT_NON_LAST_FRAME_PAYLOAD_MIN 7U
+#define FOREACH_IFACE(i) for (size_t i = 0; (i) < CANARD_IFACE_COUNT; (i)++)
+#define FOREACH_PRIO(i) for (size_t i = 0; (i) < CANARD_PRIO_COUNT; (i)++)
-#define PADDING_BYTE_VALUE 0U
+#if CANARD_IFACE_COUNT <= 2
+#define IFACE_INDEX_BITS 1U
+#elif CANARD_IFACE_COUNT <= 4
+#define IFACE_INDEX_BITS 2U
+#elif CANARD_IFACE_COUNT <= 8
+#define IFACE_INDEX_BITS 3U
+#else
+#error "Too many interfaces"
+#endif
-#define OFFSET_PRIORITY 26U
-#define OFFSET_SUBJECT_ID 8U
-#define OFFSET_SERVICE_ID 14U
-#define OFFSET_DST_NODE_ID 7U
+#define TREE_NULL (canard_tree_t){ NULL, { NULL, NULL }, 0 }
-#define FLAG_SERVICE_NOT_MESSAGE (UINT32_C(1) << 25U)
-#define FLAG_ANONYMOUS_MESSAGE (UINT32_C(1) << 24U)
-#define FLAG_REQUEST_NOT_RESPONSE (UINT32_C(1) << 24U)
-#define FLAG_RESERVED_23 (UINT32_C(1) << 23U)
-#define FLAG_RESERVED_07 (UINT32_C(1) << 7U)
+#define KILO 1000LL
+#define MEGA (KILO * KILO)
-#define TAIL_START_OF_TRANSFER 128U
-#define TAIL_END_OF_TRANSFER 64U
-#define TAIL_TOGGLE 32U
+#define DLC_BITS 4U
+
+const uint_least8_t canard_dlc_to_len[16] = { 0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64 };
+const uint_least8_t canard_len_to_dlc[65] = {
+ 0, 1, 2, 3, 4, 5, 6, 7, 8, // 0-8
+ 9, 9, 9, 9, // 9-12
+ 10, 10, 10, 10, // 13-16
+ 11, 11, 11, 11, // 17-20
+ 12, 12, 12, 12, // 21-24
+ 13, 13, 13, 13, 13, 13, 13, 13, // 25-32
+ 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, // 33-48
+ 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, // 49-64
+};
+
+static size_t smaller(const size_t a, const size_t b) { return (a < b) ? a : b; }
+static canard_us_t later(const canard_us_t a, const canard_us_t b) { return (a > b) ? a : b; }
+
+// Used if intrinsics are not available.
+// http://en.wikipedia.org/wiki/Hamming_weight#Efficient_implementation
+static byte_t popcount_emulated(uint64_t x)
+{
+ const uint64_t m1 = 0x5555555555555555ULL;
+ const uint64_t m2 = 0x3333333333333333ULL;
+ const uint64_t m4 = 0x0F0F0F0F0F0F0F0FULL;
+ const uint64_t h01 = 0x0101010101010101ULL;
+ x -= (x >> 1U) & m1;
+ x = (x & m2) + ((x >> 2U) & m2);
+ x = (x + (x >> 4U)) & m4;
+ return (byte_t)((x * h01) >> 56U);
+}
+
+static byte_t popcount(const uint64_t x)
+{
+ (void)popcount_emulated; // Avoid unused function warning if intrinsics are available.
+#ifdef stdc_count_ones
+ return (byte_t)stdc_count_ones(x); // C23 feature
+#elif defined(__GNUC__) || defined(__clang__) || defined(__CC_ARM)
+ return (byte_t)__builtin_popcountll(x);
+#else
+ return popcount_emulated(x);
+#endif
+}
+
+// The splitmix64 PRNG algorithm. Original work by Sebastiano Vigna, released under CC0-1.0 (public domain dedication).
+// Source http://xoshiro.di.unimi.it/splitmix64.c.
+static uint64_t splitmix64(uint64_t* const state)
+{
+ uint64_t z = (*state += 0x9E3779B97F4A7C15ULL);
+ z = (z ^ (z >> 30U)) * 0xBF58476D1CE4E5B9ULL;
+ z = (z ^ (z >> 27U)) * 0x94D049BB133111EBULL;
+ return z ^ (z >> 31U);
+}
+
+// Obtains a decent-quality pseudo-random number in [0, bound). Returns 0 if bound<=1
+static uint64_t random(canard_t* const self, const uint64_t bound)
+{
+ return (bound > 0) ? (splitmix64(&self->prng_state) % bound) : 0;
+}
+
+// Returns true with a probability of approximately 1/p_reciprocal. If p_reciprocal<=1, result is always true.
+static bool chance(canard_t* const self, const uint64_t p_reciprocal) { return random(self, p_reciprocal) == 0; }
+
+// Least significant bit at limb #0, bit #0.
+static void bitmap_set(uint64_t* const b, const size_t i) { b[i / 64U] |= (UINT64_C(1) << (i % 64U)); }
+static bool bitmap_test(const uint64_t* const b, const size_t i) { return (b[i / 64U] & (1ULL << (i % 64U))) != 0; }
-#define INITIAL_TOGGLE_STATE true
+static void* mem_alloc(const canard_mem_t memory, const size_t size) { return memory.vtable->alloc(memory, size); }
+static void* mem_alloc_zero(const canard_mem_t memory, const size_t size)
+{
+ void* const ptr = mem_alloc(memory, size);
+ if (ptr != NULL) {
+ (void)memset(ptr, 0, size); // NOLINT(*-security.insecureAPI.DeprecatedOrUnsafeBufferHandling)
+ }
+ return ptr;
+}
-// --------------------------------------------- TRANSFER CRC ---------------------------------------------
+static void mem_free(const canard_mem_t memory, const size_t size, void* const data)
+{
+ if (data != NULL) {
+ memory.vtable->free(memory, size, data);
+ }
+}
+
+static bool mem_valid(const canard_mem_t memory)
+{
+ return (memory.vtable != NULL) && (memory.vtable->alloc != NULL) && (memory.vtable->free != NULL);
+}
-typedef uint16_t TransferCRC;
+// --------------------------------------------- CRC ---------------------------------------------
#define CRC_INITIAL 0xFFFFU
#define CRC_RESIDUE 0x0000U
-#define CRC_SIZE_BYTES 2U
+#define CRC_BYTES 2U
-#if (CANARD_CRC_TABLE != 0)
-static const uint16_t CRCTable[256] = {
+static const uint16_t crc_table[256] = {
0x0000U, 0x1021U, 0x2042U, 0x3063U, 0x4084U, 0x50A5U, 0x60C6U, 0x70E7U, 0x8108U, 0x9129U, 0xA14AU, 0xB16BU, 0xC18CU,
0xD1ADU, 0xE1CEU, 0xF1EFU, 0x1231U, 0x0210U, 0x3273U, 0x2252U, 0x52B5U, 0x4294U, 0x72F7U, 0x62D6U, 0x9339U, 0x8318U,
0xB37BU, 0xA35AU, 0xD3BDU, 0xC39CU, 0xF3FFU, 0xE3DEU, 0x2462U, 0x3443U, 0x0420U, 0x1401U, 0x64E6U, 0x74C7U, 0x44A4U,
@@ -103,1428 +189,1885 @@ static const uint16_t CRCTable[256] = {
0x5C64U, 0x4C45U, 0x3CA2U, 0x2C83U, 0x1CE0U, 0x0CC1U, 0xEF1FU, 0xFF3EU, 0xCF5DU, 0xDF7CU, 0xAF9BU, 0xBFBAU, 0x8FD9U,
0x9FF8U, 0x6E17U, 0x7E36U, 0x4E55U, 0x5E74U, 0x2E93U, 0x3EB2U, 0x0ED1U, 0x1EF0U,
};
-#endif
-CANARD_PRIVATE TransferCRC crcAddByte(const TransferCRC crc, const uint8_t byte)
+static uint16_t crc_add_byte(const uint16_t crc, const byte_t byte)
{
-#if (CANARD_CRC_TABLE != 0)
- return (uint16_t) ((uint16_t) (crc << BITS_PER_BYTE) ^
- CRCTable[(uint16_t) ((uint16_t) (crc >> BITS_PER_BYTE) ^ byte) & BYTE_MAX]);
-#else
- static const TransferCRC Top = 0x8000U;
- static const TransferCRC Poly = 0x1021U;
- TransferCRC out = crc ^ (uint16_t) ((uint16_t) (byte) << BITS_PER_BYTE);
- // Consider adding a compilation option that replaces this with a CRC table. Adds 512 bytes of ROM.
- // Do not fold this into a loop because a size-optimizing compiler won't unroll it degrading the performance.
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U));
- return out;
-#endif
+ return (uint16_t)((uint16_t)(crc << 8U) ^ crc_table[(uint16_t)((uint16_t)(crc >> 8U) ^ byte) & BYTE_MAX]);
}
-CANARD_PRIVATE TransferCRC crcAdd(const TransferCRC crc, const struct CanardPayload payload)
+static uint16_t crc_add(const uint16_t crc, const size_t size, const void* const data)
{
- CANARD_ASSERT((payload.data != NULL) || (payload.size == 0U));
- TransferCRC out = crc;
- const uint8_t* p = (const uint8_t*) payload.data;
- for (size_t i = 0; i < payload.size; i++)
- {
- out = crcAddByte(out, *p);
+ CANARD_ASSERT((data != NULL) || (size == 0U));
+ uint16_t out = crc;
+ const byte_t* p = (const byte_t*)data;
+ for (size_t i = 0; i < size; i++) {
+ out = crc_add_byte(out, *p);
++p;
}
return out;
}
-// --------------------------------------------- TRANSMISSION ---------------------------------------------
+static uint16_t crc_add_chain(uint16_t crc, const canard_bytes_chain_t chain) // NOLINT(*-no-recursion)
+{
+ crc = crc_add(crc, chain.bytes.size, chain.bytes.data);
+ return (chain.next == NULL) ? crc : crc_add_chain(crc, *chain.next);
+}
+
+// --------------------------------------------- LIST CONTAINER ---------------------------------------------
-/// Chain of TX frames prepared for insertion into a TX queue.
-typedef struct
+// No effect if not in the list.
+static void delist(canard_list_t* const list, canard_listed_t* const member)
{
- struct CanardTxQueueItem* head;
- struct CanardTxQueueItem* tail;
- size_t size;
-} TxChain;
+ if (member->next != NULL) {
+ member->next->prev = member->prev;
+ }
+ if (member->prev != NULL) {
+ member->prev->next = member->next;
+ }
+ if (list->head == member) {
+ list->head = member->next;
+ }
+ if (list->tail == member) {
+ list->tail = member->prev;
+ }
+ member->next = NULL;
+ member->prev = NULL;
+ CANARD_ASSERT((list->head != NULL) == (list->tail != NULL));
+}
-CANARD_PRIVATE uint32_t txMakeMessageSessionSpecifier(const CanardPortID subject_id, const CanardNodeID src_node_id)
+// Insert addendum before anchor. If anchor is NULL, insert at the tail.
+// If the item is already in the list, it will be delisted first. Can be used for moving to the specified position.
+static void enlist_before(canard_list_t* const list, canard_listed_t* const anchor, canard_listed_t* const addendum)
{
- CANARD_ASSERT(src_node_id <= CANARD_NODE_ID_MAX);
- CANARD_ASSERT(subject_id <= CANARD_SUBJECT_ID_MAX);
- const uint32_t tmp = subject_id | (CANARD_SUBJECT_ID_MAX + 1) | ((CANARD_SUBJECT_ID_MAX + 1) * 2);
- return src_node_id | (tmp << OFFSET_SUBJECT_ID);
+ delist(list, addendum);
+ CANARD_ASSERT((addendum->next == NULL) && (addendum->prev == NULL));
+ CANARD_ASSERT((list->head != NULL) == (list->tail != NULL));
+ if (anchor == NULL) {
+ addendum->prev = list->tail;
+ if (list->tail != NULL) {
+ list->tail->next = addendum;
+ }
+ list->tail = addendum;
+ if (list->head == NULL) {
+ list->head = addendum;
+ }
+ } else {
+ addendum->next = anchor;
+ addendum->prev = anchor->prev;
+ if (anchor->prev != NULL) {
+ anchor->prev->next = addendum;
+ } else {
+ list->head = addendum;
+ }
+ anchor->prev = addendum;
+ }
+ CANARD_ASSERT((list->head != NULL) && (list->tail != NULL));
}
-CANARD_PRIVATE uint32_t txMakeServiceSessionSpecifier(const CanardPortID service_id,
- const bool request_not_response,
- const CanardNodeID src_node_id,
- const CanardNodeID dst_node_id)
+// If the item is already in the list, it will be delisted first. Can be used for moving to the front/back.
+static void enlist_tail(canard_list_t* const list, canard_listed_t* const member) { enlist_before(list, NULL, member); }
+
+#define LIST_TAIL(list, owner_type, owner_field) LIST_MEMBER((list).tail, owner_type, owner_field)
+#define LIST_HEAD(list, owner_type, owner_field) LIST_MEMBER((list).head, owner_type, owner_field)
+
+#define LIST_NEXT(member, owner_type, owner_field) LIST_MEMBER((member)->owner_field.next, owner_type, owner_field)
+#define LIST_PREV(member, owner_type, owner_field) LIST_MEMBER((member)->owner_field.prev, owner_type, owner_field)
+
+#define LIST_MEMBER(ptr, owner_type, owner_field) ((owner_type*)ptr_unbias((ptr), offsetof(owner_type, owner_field)))
+static void* ptr_unbias(const void* const ptr, const size_t offset)
{
- CANARD_ASSERT(src_node_id <= CANARD_NODE_ID_MAX);
- CANARD_ASSERT(dst_node_id <= CANARD_NODE_ID_MAX);
- CANARD_ASSERT(service_id <= CANARD_SERVICE_ID_MAX);
- return src_node_id | (((uint32_t) dst_node_id) << OFFSET_DST_NODE_ID) | //
- (((uint32_t) service_id) << OFFSET_SERVICE_ID) | //
- (request_not_response ? FLAG_REQUEST_NOT_RESPONSE : 0U) | FLAG_SERVICE_NOT_MESSAGE;
+ return (ptr == NULL) ? NULL : (void*)((char*)ptr - offset);
}
-/// This is the transport MTU rounded up to next full DLC minus the tail byte.
-CANARD_PRIVATE size_t adjustPresentationLayerMTU(const size_t mtu_bytes)
+#define LIST_NULL \
+ (canard_listed_t) { .next = NULL, .prev = NULL }
+
+// --------------------------------------------- SCATTERED BYTES READER ---------------------------------------------
+
+typedef struct
{
- const size_t max_index = (sizeof(CanardCANLengthToDLC) / sizeof(CanardCANLengthToDLC[0])) - 1U;
- size_t mtu = 0U;
- if (mtu_bytes < CANARD_MTU_CAN_CLASSIC)
- {
- mtu = CANARD_MTU_CAN_CLASSIC;
+ const canard_bytes_chain_t* cursor; // Initially points at the head.
+ size_t position; // Position within the current fragment, initially zero.
+} bytes_chain_reader_t;
+
+// Sequentially reads data from a scattered byte array into a contiguous destination buffer.
+// Requires that the total amount of read data does not exceed the total size of the scattered array.
+static void bytes_chain_read(bytes_chain_reader_t* const reader, const size_t size, void* const destination)
+{
+ CANARD_ASSERT((reader != NULL) && (reader->cursor != NULL) && (destination != NULL));
+ byte_t* ptr = (byte_t*)destination;
+ size_t remaining = size;
+ while (remaining > 0U) {
+ CANARD_ASSERT(reader->position <= reader->cursor->bytes.size);
+ while (reader->position == reader->cursor->bytes.size) { // Advance while skipping empty fragments.
+ reader->position = 0U;
+ reader->cursor = reader->cursor->next;
+ CANARD_ASSERT(reader->cursor != NULL);
+ }
+ CANARD_ASSERT(reader->position < reader->cursor->bytes.size);
+ const size_t progress = smaller(remaining, reader->cursor->bytes.size - reader->position);
+ CANARD_ASSERT((progress > 0U) && (progress <= remaining));
+ CANARD_ASSERT((reader->position + progress) <= reader->cursor->bytes.size);
+ // NOLINTNEXTLINE(*DeprecatedOrUnsafeBufferHandling)
+ (void)memcpy(ptr, ((const byte_t*)reader->cursor->bytes.data) + reader->position, progress);
+ ptr += progress;
+ remaining -= progress;
+ reader->position += progress;
}
- else if (mtu_bytes <= max_index)
- {
- mtu = CanardCANDLCToLength[CanardCANLengthToDLC[mtu_bytes]]; // Round up to nearest valid length.
+}
+
+static size_t bytes_chain_size(const canard_bytes_chain_t head)
+{
+ size_t size = head.bytes.size;
+ const canard_bytes_chain_t* current = head.next;
+ while (current != NULL) {
+ size += current->bytes.size;
+ current = current->next;
}
- else
- {
- mtu = CanardCANDLCToLength[CanardCANLengthToDLC[max_index]];
+ return size;
+}
+
+static bool bytes_chain_valid(const canard_bytes_chain_t head)
+{
+ // Only check the head fragment; if it is valid, the rest are assumed valid as well.
+ return (head.bytes.data != NULL) || (head.bytes.size == 0U);
+}
+
+// --------------------------------------------- TX ---------------------------------------------
+
+// On a 32-bit platform, o1heap has a per-block overhead of sizeof(void*)*2=8 bytes, meaning that the available
+// allocation sizes are 8 B (16 B block) 24 B (32 B block), 56 B (64 B block), 120 B (128 B block), etc.
+// Size optimization is very important for Classic CAN because of its low MTU.
+// Related: https://github.com/OpenCyphal/libcanard/issues/254
+typedef struct tx_frame_t
+{
+ struct tx_frame_t* next;
+ size_t refcount : (sizeof(size_t) * CHAR_BIT) - DLC_BITS; // 268+ million ought to be enough for anybody
+ size_t dlc : DLC_BITS; // use canard_len_to_dlc[] and canard_dlc_to_len[]
+ byte_t data[];
+} tx_frame_t;
+static_assert((sizeof(void*) > 4) || ((sizeof(tx_frame_t) + CANARD_MTU_CAN_CLASSIC) <= 24),
+ "On a 32-bit platform with a half-fit heap, the full Classic CAN frame should fit in a 32-byte block");
+static_assert((sizeof(void*) > 4) || ((sizeof(tx_frame_t) + CANARD_MTU_CAN_FD) <= 120),
+ "On a 32-bit platform with a half-fit heap, the full CAN FD frame should fit in a 128-byte block");
+
+static canard_bytes_t tx_frame_view(const tx_frame_t* const frame)
+{
+ return (canard_bytes_t){ .size = canard_dlc_to_len[frame->dlc], .data = frame->data };
+}
+
+static tx_frame_t* tx_frame_from_view(const canard_bytes_t view)
+{
+ return (tx_frame_t*)ptr_unbias(view.data, offsetof(tx_frame_t, data));
+}
+
+static tx_frame_t* tx_frame_new(canard_t* const self, const size_t data_size)
+{
+ CANARD_ASSERT(data_size <= CANARD_MTU_CAN_FD);
+ CANARD_ASSERT(data_size == canard_dlc_to_len[canard_len_to_dlc[data_size]]); // NOLINT(*-security.ArrayBound)
+ tx_frame_t* const frame = (tx_frame_t*)mem_alloc(self->mem.tx_frame, sizeof(tx_frame_t) + data_size);
+ if (frame != NULL) {
+ frame->next = NULL;
+ frame->refcount = 1U;
+ frame->dlc = canard_len_to_dlc[data_size] & 15U; // NOLINT(*-security.ArrayBound)
+ // Update the count; this is decremented when the frame is freed upon refcount reaching zero.
+ self->tx.queue_size++;
}
- return mtu - 1U;
+ return frame;
}
-CANARD_PRIVATE int32_t txMakeCANID(const struct CanardTransferMetadata* const tr,
- const struct CanardPayload payload,
- const CanardNodeID local_node_id,
- const size_t presentation_layer_mtu)
+void canard_refcount_inc(const canard_bytes_t obj)
{
- CANARD_ASSERT(tr != NULL);
- CANARD_ASSERT(presentation_layer_mtu > 0);
- int32_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- if ((tr->transfer_kind == CanardTransferKindMessage) && (CANARD_NODE_ID_UNSET == tr->remote_node_id) &&
- (tr->port_id <= CANARD_SUBJECT_ID_MAX))
- {
- if (local_node_id <= CANARD_NODE_ID_MAX)
- {
- out = (int32_t) txMakeMessageSessionSpecifier(tr->port_id, local_node_id);
- CANARD_ASSERT(out >= 0);
- }
- else if (payload.size <= presentation_layer_mtu)
- {
- CANARD_ASSERT((payload.data != NULL) || (payload.size == 0U));
- const CanardNodeID c = (CanardNodeID) (crcAdd(CRC_INITIAL, payload) & CANARD_NODE_ID_MAX);
- const uint32_t spec = txMakeMessageSessionSpecifier(tr->port_id, c) | FLAG_ANONYMOUS_MESSAGE;
- CANARD_ASSERT(spec <= CAN_EXT_ID_MASK);
- out = (int32_t) spec;
- }
- else
- {
- out = -CANARD_ERROR_INVALID_ARGUMENT; // Anonymous multi-frame message trs are not allowed.
- }
+ if (obj.data != NULL) {
+ tx_frame_t* const frame = tx_frame_from_view(obj);
+ CANARD_ASSERT(frame->refcount > 0U);
+ ++frame->refcount; // TODO: if C11 is enabled, use stdatomic here
}
- else if (((tr->transfer_kind == CanardTransferKindRequest) || (tr->transfer_kind == CanardTransferKindResponse)) &&
- (tr->remote_node_id <= CANARD_NODE_ID_MAX) && (tr->port_id <= CANARD_SERVICE_ID_MAX))
- {
- if (local_node_id <= CANARD_NODE_ID_MAX)
- {
- out = (int32_t) txMakeServiceSessionSpecifier(tr->port_id,
- tr->transfer_kind == CanardTransferKindRequest,
- local_node_id,
- tr->remote_node_id);
- CANARD_ASSERT(out >= 0);
- }
- else
- {
- out = -CANARD_ERROR_INVALID_ARGUMENT; // Anonymous service transfers are not allowed.
+}
+
+void canard_refcount_dec(canard_t* const self, const canard_bytes_t obj)
+{
+ if (obj.data != NULL) {
+ tx_frame_t* const frame = tx_frame_from_view(obj);
+ CANARD_ASSERT(frame->refcount > 0U); // NOLINT(*-security.ArrayBound)
+ CANARD_ASSERT(canard_dlc_to_len[frame->dlc] == obj.size);
+ frame->refcount--;
+ if (frame->refcount == 0U) {
+ CANARD_ASSERT(self->tx.queue_size > 0U);
+ self->tx.queue_size--;
+ mem_free(self->mem.tx_frame, sizeof(tx_frame_t) + obj.size, frame);
}
}
- else
- {
- out = -CANARD_ERROR_INVALID_ARGUMENT;
+}
+
+// Everything except the local node-ID. The node-ID is not needed because it may be changed while the transfer
+// is enqueued if a collision is detected; also, it is easy to add, and it is the same for all enqueued transfers,
+// hence it would not affect the ordering.
+#define CAN_ID_MSb_BITS (29U - 7U)
+
+// The struct must fit into a 128-byte O1Heap block in common embedded configurations.
+typedef struct tx_transfer_t
+{
+ canard_tree_t index_pending[CANARD_IFACE_COUNT];
+ canard_tree_t index_deadline;
+ canard_listed_t list_agewise;
+
+ // Constant fields.
+ void* user_context;
+ canard_us_t deadline;
+ uint64_t seqno;
+ uint32_t can_id_msb : CAN_ID_MSb_BITS;
+ uint32_t fd : 1;
+ uint32_t multi_frame : 1;
+
+ // Mutable fields that change as the transfer is making progress.
+ uint32_t first_frame_departed : 1;
+ tx_frame_t* cursor[CANARD_IFACE_COUNT];
+} tx_transfer_t;
+static_assert((CANARD_IFACE_COUNT > 2) || (sizeof(void*) > 4) || (sizeof(tx_transfer_t) <= 120),
+ "On a 32-bit platform with a half-fit heap, the TX transfer object should fit in a 128-byte block");
+
+static tx_transfer_t* tx_transfer_new(canard_t* const self,
+ const canard_us_t deadline,
+ const uint32_t can_id_template,
+ const bool fd,
+ void* const user_context)
+{
+ tx_transfer_t* const tr = mem_alloc_zero(self->mem.tx_transfer, sizeof(tx_transfer_t));
+ if (tr == NULL) {
+ self->err.oom++;
+ return NULL;
+ }
+ FOREACH_IFACE (i) {
+ tr->index_pending[i] = TREE_NULL;
}
+ tr->index_deadline = TREE_NULL;
+ tr->list_agewise = LIST_NULL;
+ tr->user_context = user_context;
+ tr->deadline = deadline;
+ tr->seqno = self->tx.seqno++;
+ tr->can_id_msb = (can_id_template >> (29U - CAN_ID_MSb_BITS)) & ((1U << CAN_ID_MSb_BITS) - 1U);
+ tr->fd = fd ? 1U : 0U;
+ tr->multi_frame = 0U;
+ tr->first_frame_departed = 0U;
+ FOREACH_IFACE (i) {
+ tr->cursor[i] = NULL;
+ }
+ return tr;
+}
- if (out >= 0)
- {
- const uint32_t prio = (uint32_t) tr->priority;
- if (prio <= CANARD_PRIORITY_MAX)
- {
- const uint32_t id = ((uint32_t) out) | (prio << OFFSET_PRIORITY);
- out = (int32_t) id;
- }
- else
- {
- out = -CANARD_ERROR_INVALID_ARGUMENT;
+static bool tx_is_pending(const canard_t* const self, const tx_transfer_t* const tr)
+{
+ FOREACH_IFACE (i) {
+ if (cavl2_is_inserted(self->tx.pending[i], &tr->index_pending[i])) {
+ CANARD_ASSERT(tr->cursor[i] != NULL);
+ return true;
}
}
- return out;
+ return false;
}
-CANARD_PRIVATE uint8_t txMakeTailByte(const bool start_of_transfer,
- const bool end_of_transfer,
- const bool toggle,
- const CanardTransferID transfer_id)
+static void tx_free_payload(canard_t* const self, tx_transfer_t* const tr)
{
- CANARD_ASSERT(start_of_transfer ? (toggle == INITIAL_TOGGLE_STATE) : true);
- return (uint8_t) ((start_of_transfer ? TAIL_START_OF_TRANSFER : 0U) |
- (end_of_transfer ? TAIL_END_OF_TRANSFER : 0U) | (toggle ? TAIL_TOGGLE : 0U) |
- (transfer_id & CANARD_TRANSFER_ID_MAX));
+ CANARD_ASSERT(tr != NULL);
+ FOREACH_IFACE (i) {
+ const tx_frame_t* frame = tr->cursor[i];
+ while (frame != NULL) {
+ const tx_frame_t* const next = frame->next;
+ canard_refcount_dec(self, tx_frame_view(frame));
+ frame = next;
+ }
+ tr->cursor[i] = NULL;
+ }
}
-/// Takes a frame payload size, returns a new size that is >=x and is rounded up to the nearest valid DLC.
-CANARD_PRIVATE size_t txRoundFramePayloadSizeUp(const size_t x)
+// Smaller CAN ID on the left, then smaller seqno on the left.
+static int32_t tx_cavl_compare_pending_order(const void* const user, const canard_tree_t* const node)
{
- CANARD_ASSERT(x < (sizeof(CanardCANLengthToDLC) / sizeof(CanardCANLengthToDLC[0])));
- // Suppressing a false-positive out-of-bounds access error from Sonar. Its control flow analyser is misbehaving.
- const size_t y = CanardCANLengthToDLC[x]; // NOSONAR
- CANARD_ASSERT(y < (sizeof(CanardCANDLCToLength) / sizeof(CanardCANDLCToLength[0])));
- return CanardCANDLCToLength[y];
+ const tx_transfer_t* const lhs = (const tx_transfer_t*)user;
+ const tx_transfer_t* const rhs = CAVL2_TO_OWNER(node, tx_transfer_t, index_pending[0]); // clang-format off
+ if (lhs->can_id_msb < rhs->can_id_msb) { return -1; }
+ if (lhs->can_id_msb > rhs->can_id_msb) { return +1; }
+ return (lhs->seqno < rhs->seqno) ? -1 : +1; // clang-format on
}
-/// The item is only allocated and initialized, but NOT included into the queue! The caller needs to do that.
-CANARD_PRIVATE struct CanardTxQueueItem* txAllocateQueueItem(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const uint32_t id,
- const CanardMicrosecond deadline_usec,
- const size_t payload_size)
+// Soonest to expire (smallest deadline) on the left, then smaller seqno on the left.
+static int32_t tx_cavl_compare_deadline(const void* const user, const canard_tree_t* const node)
{
- CANARD_ASSERT(que != NULL);
- CANARD_ASSERT(payload_size > 0U);
+ const tx_transfer_t* const lhs = (const tx_transfer_t*)user;
+ const tx_transfer_t* const rhs = CAVL2_TO_OWNER(node, tx_transfer_t, index_deadline); // clang-format off
+ if (lhs->deadline < rhs->deadline) { return -1; }
+ if (lhs->deadline > rhs->deadline) { return +1; }
+ return (lhs->seqno < rhs->seqno) ? -1 : +1; // clang-format on
+}
- // TX queue items are allocated in the memory pool of the instance.
- // These items are just TX pipeline support structures, they are not directly transfer payload data.
- // In contrast, see below allocation of the payload buffer from a different memory pool.
- struct CanardTxQueueItem* out = ins->memory.allocate(ins->memory.user_reference, sizeof(struct CanardTxQueueItem));
- if (out != NULL)
- {
- out->priority_base.up = NULL;
- out->priority_base.lr[0] = NULL;
- out->priority_base.lr[1] = NULL;
- out->priority_base.bf = 0;
-
- out->deadline_base.up = NULL;
- out->deadline_base.lr[0] = NULL;
- out->deadline_base.lr[1] = NULL;
- out->deadline_base.bf = 0;
-
- out->next_in_transfer = NULL; // Last by default.
- out->tx_deadline_usec = deadline_usec;
-
- // The payload is allocated in the memory pool of the TX queue.
- // The memory pool of the queue is supposed to be provided by the media.
- void* const payload_data = que->memory.allocate(que->memory.user_reference, payload_size);
- if (NULL != payload_data)
- {
- out->frame.payload.size = payload_size;
- out->frame.payload.data = payload_data;
- out->frame.payload.allocated_size = payload_size;
- out->frame.extended_can_id = id;
- }
- else
- {
- ins->memory.deallocate(ins->memory.user_reference, sizeof(struct CanardTxQueueItem), out);
- out = NULL;
+static void tx_make_pending(canard_t* const self, tx_transfer_t* const tr)
+{
+ FOREACH_IFACE (i) { // Enqueue for transmission unless it's there already (stalled interface?)
+ if ((tr->cursor[i] != NULL) && !cavl2_is_inserted(self->tx.pending[i], &tr->index_pending[i])) {
+ const canard_tree_t* const tree = cavl2_find_or_insert(
+ &self->tx.pending[i], tr, tx_cavl_compare_pending_order, &tr->index_pending[i], cavl2_trivial_factory);
+ CANARD_ASSERT(tree == &tr->index_pending[i]);
+ (void)tree;
}
}
- return out;
}
-/// Frames with identical CAN ID that are added later always compare greater than their counterparts with same CAN ID.
-/// This ensures that CAN frames with the same CAN ID are transmitted in the FIFO order.
-/// Frames that should be transmitted earlier compare smaller (i.e., put on the left side of the tree).
-CANARD_PRIVATE ptrdiff_t txAVLPriorityPredicate( //
- const void* const user_reference,
- const struct CanardTreeNode* const node)
-{
- typedef struct CanardTxQueueItem TxItem;
-
- const TxItem* const target = CAVL2_TO_OWNER(user_reference, TxItem, priority_base);
- const TxItem* const other = CAVL2_TO_OWNER(node, TxItem, priority_base);
- CANARD_ASSERT((target != NULL) && (other != NULL));
- return (target->frame.extended_can_id >= other->frame.extended_can_id) ? +1 : -1;
-}
-
-/// Frames with identical deadline
-/// that are added later always compare greater than their counterparts with the same deadline.
-/// This ensures that CAN frames with the same deadline are, when timed out, dropped in the FIFO order.
-/// Frames that should be dropped earlier compare smaller (i.e., put on the left side of the tree).
-CANARD_PRIVATE ptrdiff_t txAVLDeadlinePredicate( //
- const void* const user_reference, // NOSONAR Cavl API requires pointer to non-const.
- const struct CanardTreeNode* const node)
-{
- typedef struct CanardTxQueueItem TxItem;
-
- const TxItem* const target = CAVL2_TO_OWNER(user_reference, TxItem, deadline_base);
- const TxItem* const other = CAVL2_TO_OWNER(node, TxItem, deadline_base);
- CANARD_ASSERT((target != NULL) && (other != NULL));
- return (target->tx_deadline_usec >= other->tx_deadline_usec) ? +1 : -1;
-}
-
-/// Returns the number of frames enqueued or error (i.e., =1 or <0).
-CANARD_PRIVATE int32_t txPushSingleFrame(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond deadline_usec,
- const uint32_t can_id,
- const CanardTransferID transfer_id,
- const struct CanardPayload payload)
-{
- CANARD_ASSERT((que != NULL) && (ins != NULL));
- CANARD_ASSERT((payload.data != NULL) || (payload.size == 0));
- const size_t frame_payload_size = txRoundFramePayloadSizeUp(payload.size + 1U);
- CANARD_ASSERT(frame_payload_size > payload.size);
- const size_t padding_size = frame_payload_size - payload.size - 1U;
- CANARD_ASSERT((padding_size + payload.size + 1U) == frame_payload_size);
- int32_t out = 0;
- struct CanardTxQueueItem* const tqi =
- (que->size < que->capacity) ? txAllocateQueueItem(que, ins, can_id, deadline_usec, frame_payload_size) : NULL;
- if (tqi != NULL)
- {
- if (payload.size > 0U) // The check is needed to avoid calling memcpy() with a NULL pointer, it's an UB.
- {
- CANARD_ASSERT(payload.data != NULL);
- // Clang-Tidy raises an error recommending the use of memcpy_s() instead.
- // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability.
- (void) memcpy(tqi->frame.payload.data, payload.data, payload.size); // NOLINT
- }
- // Clang-Tidy raises an error recommending the use of memset_s() instead.
- // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability.
- uint8_t* const frame_bytes = tqi->frame.payload.data;
- (void) memset(frame_bytes + payload.size, PADDING_BYTE_VALUE, padding_size); // NOLINT
- *(frame_bytes + (frame_payload_size - 1U)) = txMakeTailByte(true, true, true, transfer_id);
-
- // Insert the newly created TX item into the priority queue.
- const struct CanardTreeNode* const priority_queue_res = cavl2_find_or_insert(&que->priority_root,
- &tqi->priority_base,
- &txAVLPriorityPredicate,
- &tqi->priority_base,
- &cavl2_trivial_factory);
- (void) priority_queue_res;
- CANARD_ASSERT(priority_queue_res == &tqi->priority_base);
-
- // Insert the newly created TX item into the deadline queue.
- const struct CanardTreeNode* const deadline_queue_res = cavl2_find_or_insert(&que->deadline_root,
- &tqi->deadline_base,
- &txAVLDeadlinePredicate,
- &tqi->deadline_base,
- &cavl2_trivial_factory);
- (void) deadline_queue_res;
- CANARD_ASSERT(deadline_queue_res == &tqi->deadline_base);
-
- que->size++;
- CANARD_ASSERT(que->size <= que->capacity);
- out = 1; // One frame enqueued.
- }
- else
- {
- out = -CANARD_ERROR_OUT_OF_MEMORY;
+// Retire one transfer and release its resources.
+static void tx_retire(canard_t* const self, tx_transfer_t* const tr)
+{
+ FOREACH_IFACE (i) {
+ (void)cavl2_remove_if(&self->tx.pending[i], &tr->index_pending[i]);
}
- CANARD_ASSERT((out < 0) || (out == 1));
- return out;
+ CANARD_ASSERT(cavl2_is_inserted(self->tx.deadline, &tr->index_deadline));
+ cavl2_remove(&self->tx.deadline, &tr->index_deadline);
+ delist(&self->tx.agewise, &tr->list_agewise);
+ tx_free_payload(self, tr);
+ mem_free(self->mem.tx_transfer, sizeof(tx_transfer_t), tr);
}
-/// Produces a chain of Tx queue items for later insertion into the Tx queue. The tail is NULL if OOM.
-CANARD_PRIVATE TxChain txGenerateMultiFrameChain(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const size_t presentation_layer_mtu,
- const CanardMicrosecond deadline_usec,
- const uint32_t can_id,
- const CanardTransferID transfer_id,
- const struct CanardPayload payload)
-{
- CANARD_ASSERT(que != NULL);
- CANARD_ASSERT(presentation_layer_mtu > 0U);
- CANARD_ASSERT(payload.size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used.
- CANARD_ASSERT(payload.data != NULL);
-
- TxChain out = {.head = NULL, .tail = NULL, .size = 0U};
- const size_t payload_size_with_crc = payload.size + CRC_SIZE_BYTES;
- size_t offset = 0U;
- TransferCRC crc = crcAdd(CRC_INITIAL, payload);
- bool toggle = INITIAL_TOGGLE_STATE;
- const uint8_t* payload_ptr = (const uint8_t*) payload.data;
- while (offset < payload_size_with_crc)
- {
- out.size++;
- const size_t frame_payload_size_with_tail =
- ((payload_size_with_crc - offset) < presentation_layer_mtu)
- ? txRoundFramePayloadSizeUp((payload_size_with_crc - offset) + 1U) // Padding in the last frame only.
- : (presentation_layer_mtu + 1U);
- struct CanardTxQueueItem* const tqi =
- txAllocateQueueItem(que, ins, can_id, deadline_usec, frame_payload_size_with_tail);
- if (NULL == out.head)
- {
- out.head = tqi;
- }
- else
- {
- // C std, 6.7.2.1.15: A pointer to a structure object <...> points to its initial member, and vice versa.
- // Can't just read tqi->base because tqi may be NULL; https://github.com/OpenCyphal/libcanard/issues/203.
- out.tail->next_in_transfer = tqi;
- }
- out.tail = tqi;
- if (NULL == out.tail)
- {
- break;
- }
+static byte_t tx_make_tail_byte(const bool sot, const bool eot, const bool tog, const byte_t transfer_id)
+{
+ return (byte_t)((sot ? TAIL_SOT : 0U) | (eot ? TAIL_EOT : 0U) | (tog ? TAIL_TOGGLE : 0U) |
+ (transfer_id & CANARD_TRANSFER_ID_MAX));
+}
- // Copy the payload into the frame.
- uint8_t* const frame_bytes = tqi->frame.payload.data;
- const size_t frame_payload_size = frame_payload_size_with_tail - 1U;
- size_t frame_offset = 0U;
- if (offset < payload.size)
- {
- size_t move_size = payload.size - offset;
- if (move_size > frame_payload_size)
- {
- move_size = frame_payload_size;
- }
- // Clang-Tidy raises an error recommending the use of memcpy_s() instead.
- // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability.
- // SonarQube incorrectly detects a buffer overflow here.
- (void) memcpy(frame_bytes, payload_ptr, move_size); // NOLINT NOSONAR
- frame_offset = frame_offset + move_size;
- offset += move_size;
- payload_ptr += move_size;
- }
+// Takes a frame payload size, returns a new size that is >=x and is rounded up to the nearest valid DLC.
+static size_t tx_ceil_frame_payload_size(const size_t x)
+{
+ CANARD_ASSERT(x < (sizeof(canard_len_to_dlc) / sizeof(canard_len_to_dlc[0])));
+ return canard_dlc_to_len[canard_len_to_dlc[x]];
+}
- // Handle the last frame of the transfer: it is special because it also contains padding and CRC.
- if (offset >= payload.size)
- {
- // Insert padding -- only in the last frame. Don't forget to include padding into the CRC.
- while ((frame_offset + CRC_SIZE_BYTES) < frame_payload_size)
- {
- frame_bytes[frame_offset] = PADDING_BYTE_VALUE;
- ++frame_offset;
- crc = crcAddByte(crc, PADDING_BYTE_VALUE);
+// Builds a chain of tx_frame_t instances, or NULL if OOM.
+// This version works with Cyphal/CAN transfers. Legacy transfers require a different layout, see dedicated function.
+static tx_frame_t* tx_spool(canard_t* const self,
+ const uint16_t crc_seed,
+ const size_t mtu,
+ const byte_t transfer_id,
+ const size_t size,
+ const canard_bytes_chain_t payload)
+{
+ bytes_chain_reader_t reader = { .cursor = &payload, .position = 0U };
+ tx_frame_t* head = NULL;
+ bool toggle = true; // Cyphal transfers start with toggle==1, unlike legacy
+ if (size < mtu) { // Single-frame transfer; no CRC required -- easy case.
+ const size_t frame_size = tx_ceil_frame_payload_size(size + 1U);
+ head = tx_frame_new(self, frame_size);
+ if (head != NULL) {
+ bytes_chain_read(&reader, size, head->data);
+ // NOLINTNEXTLINE(*-security.insecureAPI.DeprecatedOrUnsafeBufferHandling)
+ memset(&head->data[size], PADDING_BYTE_VALUE, frame_size - size - 1U);
+ head->data[frame_size - 1U] = tx_make_tail_byte(true, true, toggle, transfer_id);
+ }
+ } else {
+ const size_t size_with_crc = size + CRC_BYTES;
+ size_t offset = 0U;
+ uint16_t crc = crc_seed;
+ tx_frame_t* tail = NULL;
+ while (offset < size_with_crc) {
+ const size_t frame_size_with_tail =
+ ((size_with_crc - offset) < (mtu - 1U))
+ ? tx_ceil_frame_payload_size((size_with_crc - offset) + 1U) // padding last frame only
+ : mtu;
+ tx_frame_t* const item = tx_frame_new(self, frame_size_with_tail);
+ if (NULL == head) {
+ head = item;
+ } else {
+ tail->next = item;
}
-
- // Insert the CRC.
- if ((frame_offset < frame_payload_size) && (offset == payload.size))
- {
- // SonarQube incorrectly detects a buffer overflow here.
- frame_bytes[frame_offset] = (uint8_t) (crc >> BITS_PER_BYTE); // NOSONAR
- ++frame_offset;
- ++offset;
+ tail = item;
+ // On OOM, deallocate the entire chain and quit.
+ if (NULL == tail) {
+ while (head != NULL) {
+ tx_frame_t* const next = head->next;
+ canard_refcount_dec(self, tx_frame_view(head));
+ head = next;
+ }
+ break;
}
- if ((frame_offset < frame_payload_size) && (offset > payload.size))
- {
- frame_bytes[frame_offset] = (uint8_t) (crc & BYTE_MAX);
- ++frame_offset;
- ++offset;
+ // Populate the frame contents.
+ const size_t frame_size = frame_size_with_tail - 1U;
+ size_t frame_offset = 0U;
+ if (offset < size) {
+ const size_t move_size = smaller(size - offset, frame_size);
+ bytes_chain_read(&reader, move_size, tail->data);
+ crc = crc_add(crc, move_size, tail->data);
+ frame_offset += move_size;
+ offset += move_size;
}
+ // Handle the last frame of the transfer: it is special because it also contains padding and CRC.
+ if (offset >= size) {
+ // Insert padding -- only in the last frame. Include the padding bytes into the CRC.
+ while ((frame_offset + CRC_BYTES) < frame_size) {
+ tail->data[frame_offset] = PADDING_BYTE_VALUE;
+ ++frame_offset;
+ crc = crc_add_byte(crc, PADDING_BYTE_VALUE);
+ }
+ // Insert the CRC.
+ if ((frame_offset < frame_size) && (offset == size)) {
+ tail->data[frame_offset] = (byte_t)((crc >> 8U) & BYTE_MAX); // NOLINT(*-signed-bitwise)
+ ++frame_offset;
+ ++offset;
+ }
+ if ((frame_offset < frame_size) && (offset > size)) {
+ tail->data[frame_offset] = (byte_t)(crc & BYTE_MAX);
+ ++frame_offset;
+ ++offset;
+ }
+ }
+ // Finalize the frame.
+ CANARD_ASSERT((frame_offset + 1U) == canard_dlc_to_len[tail->dlc]);
+ tail->data[frame_offset] = tx_make_tail_byte(head == tail, offset >= size_with_crc, toggle, transfer_id);
+ toggle = !toggle;
}
-
- // Finalize the frame.
- CANARD_ASSERT((frame_offset + 1U) == out.tail->frame.payload.size);
- // SonarQube incorrectly detects a buffer overflow here.
- frame_bytes[frame_offset] = // NOSONAR
- txMakeTailByte(out.head == out.tail, offset >= payload_size_with_crc, toggle, transfer_id);
- toggle = !toggle;
}
- return out;
+ return head;
}
-/// Returns the number of frames enqueued or error.
-CANARD_PRIVATE int32_t txPushMultiFrame(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const size_t presentation_layer_mtu,
- const CanardMicrosecond deadline_usec,
- const uint32_t can_id,
- const CanardTransferID transfer_id,
- const struct CanardPayload payload)
-{
- CANARD_ASSERT(que != NULL);
- CANARD_ASSERT(presentation_layer_mtu > 0U);
- CANARD_ASSERT(payload.size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used.
-
- int32_t out = 0; // The number of frames enqueued or negated error.
- const size_t payload_size_with_crc = payload.size + CRC_SIZE_BYTES;
- const size_t num_frames = ((payload_size_with_crc + presentation_layer_mtu) - 1U) / presentation_layer_mtu;
- CANARD_ASSERT(num_frames >= 2);
- if ((que->size + num_frames) <= que->capacity) // Bail early if we can see that we won't fit anyway.
- {
- const TxChain sq =
- txGenerateMultiFrameChain(que, ins, presentation_layer_mtu, deadline_usec, can_id, transfer_id, payload);
- if (sq.tail != NULL)
- {
- struct CanardTxQueueItem* next = sq.head;
- do
- {
- const struct CanardTreeNode* const priority_queue_res = cavl2_find_or_insert(&que->priority_root,
- &next->priority_base,
- &txAVLPriorityPredicate,
- &next->priority_base,
- &cavl2_trivial_factory);
- (void) priority_queue_res;
- CANARD_ASSERT(priority_queue_res == &next->priority_base);
- CANARD_ASSERT(que->priority_root != NULL);
-
- const struct CanardTreeNode* const deadline_queue_res = cavl2_find_or_insert(&que->deadline_root,
- &next->deadline_base,
- &txAVLDeadlinePredicate,
- &next->deadline_base,
- &cavl2_trivial_factory);
- (void) deadline_queue_res;
- CANARD_ASSERT(deadline_queue_res == &next->deadline_base);
- CANARD_ASSERT(que->deadline_root != NULL);
-
- next = next->next_in_transfer;
- } while (next != NULL);
- CANARD_ASSERT(num_frames == sq.size);
- que->size += sq.size;
- CANARD_ASSERT(que->size <= que->capacity);
- CANARD_ASSERT((sq.size + 0ULL) <= INT32_MAX); // +0 is to suppress warning.
- out = (int32_t) sq.size;
+// The legacy counterpart of tx_spool() for UAVCAN v0 transfers.
+// Always uses Classic CAN MTU because UAVCAN v0 does not support CAN FD.
+static tx_frame_t* tx_spool_v0(canard_t* const self,
+ const uint16_t crc_seed,
+ const byte_t transfer_id,
+ const size_t size,
+ const canard_bytes_chain_t payload)
+{
+ bool toggle = false; // in v0, toggle starts with zero; that's how v0/v1 can be distinguished
+ if (size < CANARD_MTU_CAN_CLASSIC) { // single-frame transfer
+ tx_frame_t* const item = tx_frame_new(self, size + 1U);
+ if (item != NULL) {
+ bytes_chain_reader_t reader = { .cursor = &payload, .position = 0U };
+ bytes_chain_read(&reader, size, item->data);
+ item->data[size] = tx_make_tail_byte(true, true, toggle, transfer_id);
}
- else
- {
- out = -CANARD_ERROR_OUT_OF_MEMORY;
- struct CanardTxQueueItem* head = sq.head;
- while (head != NULL)
- {
- struct CanardTxQueueItem* const next = head->next_in_transfer;
- canardTxFree(que, ins, head);
+ return item;
+ }
+ const uint16_t crc = crc_add_chain(crc_seed, payload);
+ // NOLINTNEXTLINE(*-signed-bitwise) v0 CRC is little-endian, which is not the native ordering of CRC-16-CCITT.
+ const byte_t crc_bytes[CRC_BYTES] = { (byte_t)((crc >> 0U) & BYTE_MAX), (byte_t)((crc >> 8U) & BYTE_MAX) };
+ const size_t size_total = size + CRC_BYTES;
+ const canard_bytes_chain_t payload_total = { .bytes = { .size = CRC_BYTES, .data = crc_bytes }, .next = &payload };
+ bytes_chain_reader_t reader = { .cursor = &payload_total, .position = 0U };
+ tx_frame_t* head = NULL;
+ tx_frame_t* tail = NULL;
+ size_t offset = 0U;
+ while (offset < size_total) {
+ tx_frame_t* const item = tx_frame_new(self, smaller((size_total - offset) + 1U, CANARD_MTU_CAN_CLASSIC));
+ // On OOM, deallocate the entire chain and quit.
+ if (NULL == item) {
+ while (head != NULL) {
+ tx_frame_t* const next = head->next;
+ canard_refcount_dec(self, tx_frame_view(head));
head = next;
}
+ break;
}
+ // Append the new item.
+ if (NULL == head) {
+ head = item;
+ } else {
+ CANARD_ASSERT(NULL != tail);
+ tail->next = item;
+ }
+ tail = item;
+ // Populate the frame contents.
+ const size_t progress = smaller(size_total - offset, canard_dlc_to_len[tail->dlc] - 1U);
+ bytes_chain_read(&reader, progress, tail->data);
+ offset += progress;
+ CANARD_ASSERT((progress + 1U) == canard_dlc_to_len[tail->dlc]);
+ CANARD_ASSERT(offset <= size_total);
+ tail->data[progress] = tx_make_tail_byte(head == tail, offset == size_total, toggle, transfer_id);
+ toggle = !toggle;
}
- else // We predict that we're going to run out of queue, don't bother serializing the transfer.
- {
- out = -CANARD_ERROR_OUT_OF_MEMORY;
- }
- CANARD_ASSERT((out < 0) || (out >= 2));
- return out;
+ return head;
}
-/// Returns the number of frames freed. The number is at most 1 unless drop_whole_transfer is true.
-CANARD_PRIVATE size_t txPopAndFreeTransfer(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- struct CanardTxQueueItem* const tx_item,
- const bool drop_whole_transfer)
+// When the queue is exhausted, finds a transfer to sacrifice using simple heuristics and returns it.
+// Will return NULL if there are no transfers worth sacrificing (no queue space can be reclaimed).
+// We cannot simply stop accepting new transfers when the queue is full, because it may be caused by a single
+// stalled interface holding back progress for all transfers.
+// The heuristics are subject to review and improvement.
+static tx_transfer_t* tx_sacrifice(const canard_t* const self)
{
- CANARD_ASSERT(que != NULL);
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(tx_item != NULL);
+ return LIST_HEAD(self->tx.agewise, tx_transfer_t, list_agewise);
+}
- size_t count = 0;
- struct CanardTxQueueItem* next_tx_item = tx_item;
- struct CanardTxQueueItem* tx_item_to_free = canardTxPop(que, next_tx_item);
- while (NULL != tx_item_to_free)
- {
- next_tx_item = tx_item_to_free->next_in_transfer;
- canardTxFree(que, ins, tx_item_to_free);
- if (!drop_whole_transfer)
- {
- break;
+// True on success, false if not possible to reclaim enough space.
+static bool tx_ensure_queue_space(canard_t* const self, const size_t total_frames_needed)
+{
+ if (total_frames_needed > self->tx.queue_capacity) {
+ return false; // not gonna happen
+ }
+ while (total_frames_needed > (self->tx.queue_capacity - self->tx.queue_size)) {
+ tx_transfer_t* const tr = tx_sacrifice(self);
+ if (tr == NULL) {
+ break; // We may have no transfers anymore but the CAN driver could still be holding some pending frames.
}
- count++;
- tx_item_to_free = canardTxPop(que, next_tx_item);
+ tx_retire(self, tr);
+ self->err.tx_sacrifice++;
}
- return count;
+ return total_frames_needed <= (self->tx.queue_capacity - self->tx.queue_size);
}
-/// Flushes expired transfers by comparing deadline timestamps of the pending transfers with the current time.
-/// Returns the number of expired frames.
-CANARD_PRIVATE size_t txFlushExpiredTransfers(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond now_usec)
+static size_t tx_predict_frame_count(const size_t transfer_size, const size_t mtu)
{
- CANARD_ASSERT(que != NULL);
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(now_usec > 0);
-
- size_t count = 0;
- struct CanardTreeNode* tx_node = cavl2_min(que->deadline_root);
- struct CanardTxQueueItem* tx_item = CAVL2_TO_OWNER(tx_node, struct CanardTxQueueItem, deadline_base);
- while (NULL != tx_item)
- {
- if (now_usec <= tx_item->tx_deadline_usec)
- {
- break; // The queue is sorted by deadline, so we can stop here.
- }
- count += txPopAndFreeTransfer(que, ins, tx_item, true); // drop the whole transfer
+ const size_t bytes_per_frame = mtu - 1U; // 1 byte is used for the tail byte
+ if (transfer_size <= bytes_per_frame) {
+ return 1U; // single-frame transfer
+ }
+ return ((transfer_size + CRC_BYTES + bytes_per_frame) - 1U) / bytes_per_frame; // rounding up
+}
- tx_node = cavl2_min(que->deadline_root);
- tx_item = CAVL2_TO_OWNER(tx_node, struct CanardTxQueueItem, deadline_base);
+static void tx_expire(canard_t* const self, const canard_us_t now)
+{
+ tx_transfer_t* tr = CAVL2_TO_OWNER(cavl2_min(self->tx.deadline), tx_transfer_t, index_deadline);
+ while ((tr != NULL) && (now > tr->deadline)) {
+ tx_transfer_t* const tr_next =
+ CAVL2_TO_OWNER(cavl2_next_greater(&tr->index_deadline), tx_transfer_t, index_deadline);
+ tx_retire(self, tr);
+ self->err.tx_expiration++;
+ tr = tr_next;
}
- return count;
}
-// --------------------------------------------- RECEPTION ---------------------------------------------
+// Enqueues a transfer for transmission.
+static bool tx_push(canard_t* const self,
+ tx_transfer_t* const tr,
+ const bool v0,
+ const byte_t iface_bitmap,
+ const byte_t transfer_id,
+ const canard_bytes_chain_t payload,
+ const uint16_t crc_seed)
+{
+ CANARD_ASSERT(tr != NULL);
+ CANARD_ASSERT((!tr->fd) || !v0); // The caller must ensure this.
+ CANARD_ASSERT(iface_bitmap != 0);
+
+ const canard_us_t now = self->vtable->now(self);
+
+ // Expire old transfers first to free up queue space.
+ tx_expire(self, now);
+
+ // Ensure the queue has enough space. v0 transfers always use Classic CAN regardless of tr->fd.
+ const size_t mtu = tr->fd ? CANARD_MTU_CAN_FD : CANARD_MTU_CAN_CLASSIC;
+ const size_t size = bytes_chain_size(payload);
+ const size_t n_frames = tx_predict_frame_count(size, mtu);
+ CANARD_ASSERT(n_frames > 0);
+ tr->multi_frame = n_frames > 1U;
+ if (!tx_ensure_queue_space(self, n_frames)) {
+ self->err.tx_capacity++;
+ mem_free(self->mem.tx_transfer, sizeof(tx_transfer_t), tr);
+ return false;
+ }
+
+ // Make a shared frame spool. Unlike the Cyphal/UDP implementation, we require all ifaces to use the same MTU.
+ const size_t queue_size_before = self->tx.queue_size;
+ tx_frame_t* const spool = v0 ? tx_spool_v0(self, crc_seed, transfer_id, size, payload)
+ : tx_spool(self, crc_seed, mtu, transfer_id, size, payload);
+ if (spool == NULL) {
+ self->err.oom++;
+ mem_free(self->mem.tx_transfer, sizeof(tx_transfer_t), tr);
+ return false;
+ }
+ CANARD_ASSERT((self->tx.queue_size - queue_size_before) == n_frames);
+ CANARD_ASSERT(self->tx.queue_size <= self->tx.queue_capacity);
+ (void)queue_size_before;
+
+ // Adjust the spooled frame refcounts to avoid premature deallocation.
+ const byte_t frame_refcount_inc = (byte_t)(popcount(iface_bitmap) - 1U);
+ CANARD_ASSERT(frame_refcount_inc < CANARD_IFACE_COUNT);
+ if (frame_refcount_inc > 0) {
+ tx_frame_t* frame = spool;
+ while (frame != NULL) {
+ frame->refcount += frame_refcount_inc;
+ frame = frame->next;
+ }
+ }
+
+ // Attach the spool.
+ FOREACH_IFACE (i) {
+ if ((iface_bitmap & (1U << i)) != 0) {
+ tr->cursor[i] = spool;
+ }
+ }
-#define RX_SESSIONS_PER_SUBSCRIPTION (CANARD_NODE_ID_MAX + 1U)
+ // Register the transfer and schedule for transmission.
+ const canard_tree_t* const deadline_tree = cavl2_find_or_insert(
+ &self->tx.deadline, tr, tx_cavl_compare_deadline, &tr->index_deadline, cavl2_trivial_factory);
+ CANARD_ASSERT(deadline_tree == &tr->index_deadline);
+ (void)deadline_tree;
+ enlist_tail(&self->tx.agewise, &tr->list_agewise);
+ tx_make_pending(self, tr);
+ return true;
+}
-/// The memory requirement model provided in the documentation assumes that the maximum size of this structure never
-/// exceeds 48 bytes on any conventional platform.
-/// A user that needs a detailed analysis of the worst-case memory consumption may compute the size of this structure
-/// for the particular platform at hand manually or by evaluating its sizeof().
-/// The fields are ordered to minimize the amount of padding on all conventional platforms.
-typedef struct CanardInternalRxSession
+static tx_transfer_t* tx_pending_node_to_transfer(const canard_tree_t* const node, const byte_t iface_index)
{
- CanardMicrosecond transfer_timestamp_usec; ///< Timestamp of the last received start-of-transfer.
- size_t total_payload_size; ///< The payload size before the implicit truncation, including the CRC.
- struct CanardMutablePayload payload; ///< Dynamically allocated and handed off to the application when done.
- TransferCRC calculated_crc; ///< Updated with the received payload in real time.
- CanardTransferID transfer_id;
- uint8_t redundant_iface_index; ///< Arbitrary value in [0, 255].
- bool toggle;
-} CanardInternalRxSession;
+ return (tx_transfer_t*)ptr_unbias(
+ node, offsetof(tx_transfer_t, index_pending) + (((size_t)iface_index) * sizeof(canard_tree_t)));
+}
-/// High-level transport frame model.
-typedef struct
+static void tx_eject_pending(canard_t* const self, const byte_t iface_index)
{
- CanardMicrosecond timestamp_usec;
- enum CanardPriority priority;
- enum CanardTransferKind transfer_kind;
- CanardPortID port_id;
- CanardNodeID source_node_id;
- CanardNodeID destination_node_id;
- CanardTransferID transfer_id;
- bool start_of_transfer;
- bool end_of_transfer;
- bool toggle;
- struct CanardPayload payload;
-} RxFrameModel;
-
-/// Returns truth if the frame is valid and parsed successfully. False if the frame is not a valid Cyphal/CAN frame.
-CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec,
- const struct CanardFrame* const frame,
- RxFrameModel* const out)
-{
- CANARD_ASSERT(frame != NULL);
- CANARD_ASSERT(frame->extended_can_id <= CAN_EXT_ID_MASK);
- CANARD_ASSERT(out != NULL);
- bool valid = false;
- if (frame->payload.size > 0)
- {
- CANARD_ASSERT(frame->payload.data != NULL);
- out->timestamp_usec = timestamp_usec;
-
- // CAN ID parsing.
- const uint32_t can_id = frame->extended_can_id;
- out->priority = (enum CanardPriority)((can_id >> OFFSET_PRIORITY) & CANARD_PRIORITY_MAX);
- out->source_node_id = (CanardNodeID) (can_id & CANARD_NODE_ID_MAX);
- if (0 == (can_id & FLAG_SERVICE_NOT_MESSAGE))
- {
- out->transfer_kind = CanardTransferKindMessage;
- out->port_id = (CanardPortID) ((can_id >> OFFSET_SUBJECT_ID) & CANARD_SUBJECT_ID_MAX);
- if ((can_id & FLAG_ANONYMOUS_MESSAGE) != 0)
- {
- out->source_node_id = CANARD_NODE_ID_UNSET;
- }
- out->destination_node_id = CANARD_NODE_ID_UNSET;
- // Reserved bits may be unreserved in the future.
- valid = (0 == (can_id & FLAG_RESERVED_23)) && (0 == (can_id & FLAG_RESERVED_07));
+ while (true) {
+ const canard_tree_t* const pending = cavl2_min(self->tx.pending[iface_index]);
+ if (pending == NULL) {
+ break;
}
- else
- {
- out->transfer_kind =
- ((can_id & FLAG_REQUEST_NOT_RESPONSE) != 0) ? CanardTransferKindRequest : CanardTransferKindResponse;
- out->port_id = (CanardPortID) ((can_id >> OFFSET_SERVICE_ID) & CANARD_SERVICE_ID_MAX);
- out->destination_node_id = (CanardNodeID) ((can_id >> OFFSET_DST_NODE_ID) & CANARD_NODE_ID_MAX);
- // The reserved bit may be unreserved in the future. It may be used to extend the service-ID to 10 bits.
- // Per Specification, source cannot be the same as the destination.
- valid = (0 == (can_id & FLAG_RESERVED_23)) && (out->source_node_id != out->destination_node_id);
+ tx_transfer_t* const tr = tx_pending_node_to_transfer(pending, iface_index);
+ CANARD_ASSERT(tr->cursor[iface_index] != NULL);
+
+ // Try to eject one frame.
+ const tx_frame_t* const frame = tr->cursor[iface_index];
+ tx_frame_t* const frame_next = frame->next;
+ // Clangd/Clang-Tidy bug: bitfield integer promotion rules are modeled incorrectly -- the cast is not redundant.
+ const uint32_t can_id = ((uint32_t)tr->can_id_msb << 7U) | self->node_id; // NOLINT(*-readability-casting)
+ const bool ejected = self->vtable->tx(
+ self, tr->user_context, tr->deadline, iface_index, tr->fd != 0U, can_id, tx_frame_view(frame));
+ if (!ejected) {
+ break;
}
- // Payload parsing.
- out->payload.size = frame->payload.size - 1U; // Cut off the tail byte.
- out->payload.data = frame->payload.data;
-
- // Tail byte parsing.
- // Intentional violation of MISRA: pointer arithmetics is required to locate the tail byte. Unavoidable.
- const uint8_t tail = *(((const uint8_t*) out->payload.data) + out->payload.size); // NOSONAR
- out->transfer_id = tail & CANARD_TRANSFER_ID_MAX;
- out->start_of_transfer = ((tail & TAIL_START_OF_TRANSFER) != 0);
- out->end_of_transfer = ((tail & TAIL_END_OF_TRANSFER) != 0);
- out->toggle = ((tail & TAIL_TOGGLE) != 0);
-
- // Final validation.
- // Protocol version check: if SOT is set, then the toggle shall also be set.
- valid = valid && ((!out->start_of_transfer) || (INITIAL_TOGGLE_STATE == out->toggle));
- // Anonymous transfers can be only single-frame transfers.
- valid = valid &&
- ((out->start_of_transfer && out->end_of_transfer) || (CANARD_NODE_ID_UNSET != out->source_node_id));
- // Non-last frames of a multi-frame transfer shall utilize the MTU fully.
- valid = valid && ((out->payload.size >= MFT_NON_LAST_FRAME_PAYLOAD_MIN) || out->end_of_transfer);
- // A frame that is a part of a multi-frame transfer cannot be empty (tail byte not included).
- valid = valid && ((out->payload.size > 0) || (out->start_of_transfer && out->end_of_transfer));
- }
- return valid;
-}
-
-CANARD_PRIVATE void rxInitTransferMetadataFromFrame(const RxFrameModel* const frame,
- struct CanardTransferMetadata* const out_transfer)
-{
- CANARD_ASSERT(frame != NULL);
- CANARD_ASSERT(frame->payload.data != NULL);
- CANARD_ASSERT(out_transfer != NULL);
- out_transfer->priority = frame->priority;
- out_transfer->transfer_kind = frame->transfer_kind;
- out_transfer->port_id = frame->port_id;
- out_transfer->remote_node_id = frame->source_node_id;
- out_transfer->transfer_id = frame->transfer_id;
-}
-
-/// The implementation is borrowed from the Specification.
-CANARD_PRIVATE uint8_t rxComputeTransferIDDifference(const uint8_t a, const uint8_t b)
-{
- CANARD_ASSERT(a <= CANARD_TRANSFER_ID_MAX);
- CANARD_ASSERT(b <= CANARD_TRANSFER_ID_MAX);
- int16_t diff = (int16_t) (((int16_t) a) - ((int16_t) b));
- if (diff < 0)
- {
- const uint8_t modulo = 1U << CANARD_TRANSFER_ID_BIT_LENGTH;
- diff = (int16_t) (diff + (int16_t) modulo);
+ // Commit successful ejection by advancing this interface cursor.
+ tr->first_frame_departed = 1U;
+ tr->cursor[iface_index] = frame_next;
+ canard_refcount_dec(self, tx_frame_view(frame));
+
+ // If this interface is done with the transfer, remove it from this pending tree.
+ if (frame_next == NULL) {
+ (void)cavl2_remove_if(&self->tx.pending[iface_index], &tr->index_pending[iface_index]);
+ if (!tx_is_pending(self, tr)) {
+ tx_retire(self, tr);
+ }
+ }
}
- return (uint8_t) diff;
}
-CANARD_PRIVATE int8_t rxSessionWritePayload(struct CanardInstance* const ins,
- CanardInternalRxSession* const rxs,
- const size_t extent,
- const struct CanardPayload payload)
+// Cancels all pending multi-frame transfers where the first frame has already departed via at least one of the ifaces.
+// This is needed to allow safe node-ID change on collision detection, such that remotes don't reassemble multiframe
+// frankentransfers from different nodes sharing the same ID.
+// The complexity is linear in the number of enqueued transfers (not frames!).
+// This is safe to invoke from any context since it doesn't reach anywhere outside of the TX pipeline.
+static void tx_purge_continuations(canard_t* const self)
{
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(rxs != NULL);
- CANARD_ASSERT((payload.data != NULL) || (payload.size == 0U));
- CANARD_ASSERT(rxs->payload.size <= extent); // This invariant is enforced by the subscription logic.
- CANARD_ASSERT(rxs->payload.size <= rxs->total_payload_size);
-
- rxs->total_payload_size += payload.size;
-
- // Allocate the payload lazily, as late as possible.
- if ((NULL == rxs->payload.data) && (extent > 0U))
- {
- CANARD_ASSERT(rxs->payload.size == 0);
- rxs->payload.data = ins->memory.allocate(ins->memory.user_reference, extent);
- rxs->payload.allocated_size = extent;
+ tx_transfer_t* tr = LIST_HEAD(self->tx.agewise, tx_transfer_t, list_agewise);
+ while (tr != NULL) {
+ tx_transfer_t* const next = LIST_NEXT(tr, tx_transfer_t, list_agewise);
+ if ((tr->multi_frame != 0U) && (tr->first_frame_departed != 0U)) {
+ tx_retire(self, tr);
+ }
+ tr = next;
}
+}
- int8_t out = 0;
- if (rxs->payload.data != NULL)
- {
- // Copy the payload into the contiguous buffer. Apply the implicit truncation rule if necessary.
- size_t bytes_to_copy = payload.size;
- if ((rxs->payload.size + bytes_to_copy) > extent)
- {
- CANARD_ASSERT(rxs->payload.size <= extent);
- bytes_to_copy = extent - rxs->payload.size;
- CANARD_ASSERT((rxs->payload.size + bytes_to_copy) == extent);
- CANARD_ASSERT(bytes_to_copy < payload.size);
+uint_least8_t canard_pending_ifaces(const canard_t* const self)
+{
+ uint_least8_t out = 0;
+ if (self != NULL) {
+ FOREACH_IFACE (i) {
+ out |= (self->tx.pending[i] != NULL) ? (uint_least8_t)(1U << i) : 0U;
}
- // This memcpy() call here is one of the two variable-complexity operations in the RX pipeline;
- // the other one is the search of the matching subscription state.
- // Excepting these two cases, the entire RX pipeline contains neither loops nor recursion.
- // Intentional violation of MISRA: indexing on a pointer. This is done to avoid pointer arithmetics.
- // Clang-Tidy raises an error recommending the use of memcpy_s() instead.
- // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability.
- (void) memcpy(((uint8_t*) rxs->payload.data) + rxs->payload.size, // NOLINT NOSONAR
- payload.data,
- bytes_to_copy);
- rxs->payload.size += bytes_to_copy;
- CANARD_ASSERT(rxs->payload.size <= extent);
- CANARD_ASSERT(rxs->payload.size <= rxs->payload.allocated_size);
- }
- else
- {
- CANARD_ASSERT(rxs->payload.size == 0);
- out = (extent > 0U) ? -CANARD_ERROR_OUT_OF_MEMORY : 0;
}
- CANARD_ASSERT(out <= 0);
return out;
}
-CANARD_PRIVATE void rxSessionRestart(struct CanardInstance* const ins, CanardInternalRxSession* const rxs)
-{
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(rxs != NULL);
- // `rxs->payload.data` may be NULL, which is OK.
- ins->memory.deallocate(ins->memory.user_reference, rxs->payload.allocated_size, rxs->payload.data);
- rxs->total_payload_size = 0U;
- rxs->payload.size = 0U;
- rxs->payload.data = NULL;
- rxs->payload.allocated_size = 0U;
- rxs->calculated_crc = CRC_INITIAL;
- rxs->transfer_id = (CanardTransferID) ((rxs->transfer_id + 1U) & CANARD_TRANSFER_ID_MAX);
- // The transport index is retained.
- rxs->toggle = INITIAL_TOGGLE_STATE;
-}
-
-CANARD_PRIVATE int8_t rxSessionAcceptFrame(struct CanardInstance* const ins,
- CanardInternalRxSession* const rxs,
- const RxFrameModel* const frame,
- const size_t extent,
- struct CanardRxTransfer* const out_transfer)
-{
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(rxs != NULL);
- CANARD_ASSERT(frame != NULL);
- CANARD_ASSERT(frame->payload.data != NULL);
- CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX);
- CANARD_ASSERT(out_transfer != NULL);
-
- if (frame->start_of_transfer) // The transfer timestamp is the timestamp of its first frame.
- {
- rxs->transfer_timestamp_usec = frame->timestamp_usec;
+bool canard_publish_16b(canard_t* const self,
+ const canard_us_t deadline,
+ const uint_least8_t iface_bitmap,
+ const canard_prio_t priority,
+ const uint16_t subject_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ bool ok =
+ (self != NULL) && (priority < CANARD_PRIO_COUNT) && bytes_chain_valid(payload) &&
+ (((iface_bitmap & CANARD_IFACE_BITMAP_ALL) != 0) && ((iface_bitmap & CANARD_IFACE_BITMAP_ALL) == iface_bitmap));
+ if (ok) {
+ // v1.1 16-bit message format extends the subject-ID to 16 bits, using bit 7 as 1 to discriminate from v1.0,
+ // and designating the anonymous bit as reserved=0. ID bit layout:
+ //
+ // 28 27 26 25 24 23 22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
+ // |prio[3] |sv| 0| subject_id[16] | 1| source_node_id[7] |
+ //
+ // In DSDL notation:
+ //
+ // uint7 source_node_id
+ // bool reserved_7 # =1, version discrimination
+ // uint16 subject_id
+ // bool reserved_24 # =0, was anonymous
+ // bool service_not_message # =0
+ // uint3 priority
+ const uint32_t can_id =
+ (((uint32_t)priority) << PRIO_SHIFT) | ((uint32_t)subject_id << 8U) | (UINT32_C(1) << 7U);
+ tx_transfer_t* const tr = tx_transfer_new(self, deadline, can_id, self->tx.fd, user_context);
+ ok = (tr != NULL) && tx_push(self, tr, false, iface_bitmap, transfer_id, payload, CRC_INITIAL);
}
+ return ok;
+}
- const bool single_frame = frame->start_of_transfer && frame->end_of_transfer;
- if (!single_frame)
- {
- // Update the CRC. Observe that the implicit truncation rule may apply here: the payload may be
- // truncated, but its CRC is validated always anyway.
- rxs->calculated_crc = crcAdd(rxs->calculated_crc, frame->payload);
+bool canard_publish_13b(canard_t* const self,
+ const canard_us_t deadline,
+ const uint_least8_t iface_bitmap,
+ const canard_prio_t priority,
+ const uint16_t subject_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ bool ok =
+ (self != NULL) && (priority < CANARD_PRIO_COUNT) && bytes_chain_valid(payload) &&
+ (((iface_bitmap & CANARD_IFACE_BITMAP_ALL) != 0) && ((iface_bitmap & CANARD_IFACE_BITMAP_ALL) == iface_bitmap)) &&
+ (subject_id <= CANARD_SUBJECT_ID_MAX_13b);
+ if (ok) {
+ const uint32_t can_id =
+ (((uint32_t)priority) << PRIO_SHIFT) | (UINT32_C(3) << 21U) | (((uint32_t)subject_id) << 8U);
+ tx_transfer_t* const tr = tx_transfer_new(self, deadline, can_id, self->tx.fd, user_context);
+ ok = (tr != NULL) && tx_push(self, tr, false, iface_bitmap, transfer_id, payload, CRC_INITIAL);
}
+ return ok;
+}
- int8_t out = rxSessionWritePayload(ins, rxs, extent, frame->payload);
- if (out < 0)
- {
- CANARD_ASSERT(-CANARD_ERROR_OUT_OF_MEMORY == out);
- rxSessionRestart(ins, rxs); // Out-of-memory.
+static bool tx_1v0_service(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint16_t service_id,
+ const uint_least8_t destination_node_id,
+ const bool request_not_response,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ bool ok = (self != NULL) && (priority < CANARD_PRIO_COUNT) && bytes_chain_valid(payload) &&
+ (service_id <= CANARD_SERVICE_ID_MAX) && (destination_node_id <= CANARD_NODE_ID_MAX);
+ if (ok) {
+ const uint32_t can_id = (((uint32_t)priority) << PRIO_SHIFT) | (UINT32_C(1) << 25U) |
+ (request_not_response ? (UINT32_C(1) << 24U) : 0U) | (((uint32_t)service_id) << 14U) |
+ (((uint32_t)destination_node_id) << 7U);
+ tx_transfer_t* const tr = tx_transfer_new(self, deadline, can_id, self->tx.fd, user_context);
+ ok = (tr != NULL) && tx_push(self, tr, false, CANARD_IFACE_BITMAP_ALL, transfer_id, payload, CRC_INITIAL);
}
- else if (frame->end_of_transfer)
- {
- CANARD_ASSERT(0 == out);
- if (single_frame || (CRC_RESIDUE == rxs->calculated_crc))
- {
- out = 1; // One transfer received, notify the application.
- rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata);
- out_transfer->timestamp_usec = rxs->transfer_timestamp_usec;
- out_transfer->payload = rxs->payload;
-
- // Cut off the CRC from the payload if it's there -- we don't want to expose it to the user.
- CANARD_ASSERT(rxs->total_payload_size >= rxs->payload.size);
- const size_t truncated_amount = rxs->total_payload_size - rxs->payload.size;
- if ((!single_frame) && (CRC_SIZE_BYTES > truncated_amount)) // Single-frame transfers don't have CRC.
- {
- CANARD_ASSERT(out_transfer->payload.size >= (CRC_SIZE_BYTES - truncated_amount));
- out_transfer->payload.size -= CRC_SIZE_BYTES - truncated_amount;
- }
+ return ok;
+}
- // Ownership passed over to the application, nullify to prevent freeing.
- rxs->payload.size = 0U;
- rxs->payload.data = NULL;
- rxs->payload.allocated_size = 0U;
- }
- rxSessionRestart(ins, rxs); // Successful completion.
- }
- else
- {
- rxs->toggle = !rxs->toggle;
+bool canard_request(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint16_t service_id,
+ const uint_least8_t server_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ return tx_1v0_service(
+ self, deadline, priority, service_id, server_node_id, true, transfer_id, payload, user_context);
+}
+
+bool canard_respond(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint16_t service_id,
+ const uint_least8_t client_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ return tx_1v0_service(
+ self, deadline, priority, service_id, client_node_id, false, transfer_id, payload, user_context);
+}
+
+bool canard_v0_publish(canard_t* const self,
+ const canard_us_t deadline,
+ const uint_least8_t iface_bitmap,
+ const canard_prio_t priority,
+ const uint16_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ bool ok =
+ (self != NULL) && (priority < CANARD_PRIO_COUNT) && bytes_chain_valid(payload) &&
+ (((iface_bitmap & CANARD_IFACE_BITMAP_ALL) != 0) && ((iface_bitmap & CANARD_IFACE_BITMAP_ALL) == iface_bitmap)) &&
+ (self->node_id != 0);
+ if (ok) {
+ const uint32_t can_id = (((uint32_t)priority) << PRIO_SHIFT) | ((uint32_t)data_type_id << 8U);
+ tx_transfer_t* const tr = tx_transfer_new(self, deadline, can_id, false, user_context);
+ ok = (tr != NULL) && tx_push(self, tr, true, iface_bitmap, transfer_id, payload, crc_seed);
}
- return out;
+ return ok;
}
-/// Evaluates the state of the RX session with respect to time and the new frame, and restarts it if necessary.
-/// The next step is to accept the frame if the transfer-ID, toggle but, and transport index match; reject otherwise.
-/// The logic of this function is simple: in the most cases (see below exception) it restarts the reassembler
-/// if the start-of-transfer flag is set and any two of the three conditions are met:
-///
-/// - The frame has arrived over the same interface as the previous transfer.
-/// - New transfer-ID is detected.
-/// - The transfer-ID timeout has expired.
-///
-/// The only exception is when the transfer-ID timeout has expired and the new frame has the same transfer-ID as it
-/// was expected BUT not on the same transport as before. In this case, the reassembler is "restarted" only
-/// if the total payload size is zero (meaning that the reassembler has not been started yet), and so could be more
-/// "relaxed" and not so sticky to the transport index. This case was discovered during libcyphal development when
-/// multiple redundant transports were used in context of multiple concurrent RPC clients for the same service id.
-/// For more information see https://github.com/OpenCyphal/libcanard/issues/228
-///
-/// Notice that mere TID-timeout is not enough to restart to prevent the interface index oscillation;
-/// while this is not visible at the application layer, it may delay the transfer arrival.
-CANARD_PRIVATE void rxSessionSynchronize(CanardInternalRxSession* const rxs,
- const RxFrameModel* const frame,
- const uint8_t redundant_iface_index,
- const CanardMicrosecond transfer_id_timeout_usec)
-{
- CANARD_ASSERT(rxs != NULL);
- CANARD_ASSERT(frame != NULL);
- CANARD_ASSERT(rxs->transfer_id <= CANARD_TRANSFER_ID_MAX);
- CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX);
-
- const bool same_transport = rxs->redundant_iface_index == redundant_iface_index;
- // Examples: rxComputeTransferIDDifference(2, 3)==31
- // rxComputeTransferIDDifference(2, 2)==0
- // rxComputeTransferIDDifference(2, 1)==1
- const bool tid_match = rxs->transfer_id == frame->transfer_id;
- const bool tid_new = rxComputeTransferIDDifference(rxs->transfer_id, frame->transfer_id) > 1;
- // The transfer ID timeout is measured relative to the timestamp of the last start-of-transfer frame.
- const bool tid_timeout = (frame->timestamp_usec > rxs->transfer_timestamp_usec) &&
- ((frame->timestamp_usec - rxs->transfer_timestamp_usec) > transfer_id_timeout_usec);
- // The total payload size is zero when a new transfer reassembling has not been started yet, hence the idle.
- const bool idle = 0U == rxs->total_payload_size;
-
- const bool restartable = (same_transport && tid_new) || //
- (same_transport && tid_timeout) || //
- (tid_timeout && tid_new) || //
- (tid_timeout && tid_match && idle);
- // Restarting the transfer reassembly only makes sense if the new frame is a start of transfer.
- // Otherwise, the new transfer would be impossible to reassemble anyway since the first frame is lost.
- if (frame->start_of_transfer && restartable)
- {
- CANARD_ASSERT(frame->start_of_transfer);
- rxs->total_payload_size = 0U;
- rxs->payload.size = 0U; // The buffer is not released because we still need it.
- rxs->calculated_crc = CRC_INITIAL;
- rxs->transfer_id = frame->transfer_id;
- rxs->toggle = INITIAL_TOGGLE_STATE;
- rxs->redundant_iface_index = redundant_iface_index;
- }
-}
-
-/// RX session state machine update is the most intricate part of any Cyphal transport implementation.
-/// The state model used here is derived from the reference pseudocode given in the original UAVCAN v0 specification.
-/// The Cyphal/CAN v1 specification, which this library is an implementation of, does not provide any reference
-/// pseudocode. Instead, it takes a higher-level, more abstract approach, where only the high-level requirements
-/// are given and the particular algorithms are left to be implementation-defined. Such abstract approach is much
-/// advantageous because it allows implementers to choose whatever solution works best for the specific application at
-/// hand, while the wire compatibility is still guaranteed by the high-level requirements given in the specification.
-CANARD_PRIVATE int8_t rxSessionUpdate(struct CanardInstance* const ins,
- CanardInternalRxSession* const rxs,
- const RxFrameModel* const frame,
- const uint8_t redundant_iface_index,
- const CanardMicrosecond transfer_id_timeout_usec,
- const size_t extent,
- struct CanardRxTransfer* const out_transfer)
-{
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(rxs != NULL);
- CANARD_ASSERT(frame != NULL);
- CANARD_ASSERT(out_transfer != NULL);
- CANARD_ASSERT(rxs->transfer_id <= CANARD_TRANSFER_ID_MAX);
- CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX);
- rxSessionSynchronize(rxs, frame, redundant_iface_index, transfer_id_timeout_usec);
- int8_t out = 0;
- // The purpose of the correct_start check is to reduce the possibility of accepting a malformed multi-frame
- // transfer in the event of a CRC collision. The scenario where this failure mode would manifest is as follows:
- // 1. A valid transfer (whether single- or multi-frame) is accepted with TID=X.
- // 2. All frames of the subsequent multi-frame transfer with TID=X+1 are lost except for the last one.
- // 3. The CRC of said multi-frame transfer happens to yield the correct residue when applied to the fragment
- // of the payload contained in the last frame of the transfer (a CRC collision is in effect).
- // 4. The last frame of the multi-frame transfer is erroneously accepted even though it is malformed.
- // The correct_start check eliminates this failure mode by ensuring that the first frame is observed.
- // See https://github.com/OpenCyphal/libcanard/issues/189.
- const bool correct_iface = (rxs->redundant_iface_index == redundant_iface_index);
- const bool correct_toggle = (frame->toggle == rxs->toggle);
- const bool correct_tid = (frame->transfer_id == rxs->transfer_id);
- const bool correct_start = frame->start_of_transfer //
- ? (0 == rxs->total_payload_size)
- : (rxs->total_payload_size > 0);
- if (correct_iface && correct_toggle && correct_tid && correct_start)
- {
- out = rxSessionAcceptFrame(ins, rxs, frame, extent, out_transfer);
+static bool tx_v0_service(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t destination_node_id,
+ const bool request_not_response,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ bool ok = (self != NULL) && (priority < CANARD_PRIO_COUNT) && bytes_chain_valid(payload) && (self->node_id != 0U) &&
+ (destination_node_id > 0U) && (destination_node_id <= CANARD_NODE_ID_MAX);
+ if (ok) {
+ const uint32_t can_id = (((uint32_t)priority) << PRIO_SHIFT) | (((uint32_t)data_type_id) << 16U) |
+ (request_not_response ? (UINT32_C(1) << 15U) : 0U) |
+ (((uint32_t)destination_node_id) << 8U) | (UINT32_C(1) << 7U);
+ tx_transfer_t* const tr = tx_transfer_new(self, deadline, can_id, false, user_context);
+ ok = (tr != NULL) && tx_push(self, tr, true, CANARD_IFACE_BITMAP_ALL, transfer_id, payload, crc_seed);
}
- return out;
+ return ok;
}
-CANARD_PRIVATE int8_t rxAcceptFrame(struct CanardInstance* const ins,
- struct CanardRxSubscription* const subscription,
- const RxFrameModel* const frame,
- const uint8_t redundant_iface_index,
- struct CanardRxTransfer* const out_transfer)
+bool canard_v0_request(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t server_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
{
- CANARD_ASSERT(ins != NULL);
- CANARD_ASSERT(subscription != NULL);
- CANARD_ASSERT(subscription->port_id == frame->port_id);
- CANARD_ASSERT(frame != NULL);
- CANARD_ASSERT(frame->payload.data != NULL);
- CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX);
- CANARD_ASSERT((CANARD_NODE_ID_UNSET == frame->destination_node_id) || (ins->node_id == frame->destination_node_id));
- CANARD_ASSERT(out_transfer != NULL);
+ return tx_v0_service(
+ self, deadline, priority, data_type_id, crc_seed, server_node_id, true, transfer_id, payload, user_context);
+}
- int8_t out = 0;
- if (frame->source_node_id <= CANARD_NODE_ID_MAX)
- {
- // If such session does not exist, create it. This only makes sense if this is the first frame of a
- // transfer, otherwise, we won't be able to receive the transfer anyway so we don't bother.
- if ((NULL == subscription->sessions[frame->source_node_id]) && frame->start_of_transfer)
- {
- CanardInternalRxSession* const rxs =
- (CanardInternalRxSession*) ins->memory.allocate(ins->memory.user_reference,
- sizeof(CanardInternalRxSession));
- subscription->sessions[frame->source_node_id] = rxs;
- if (rxs != NULL)
- {
- rxs->transfer_timestamp_usec = frame->timestamp_usec;
- rxs->total_payload_size = 0U;
- rxs->payload.size = 0U;
- rxs->payload.data = NULL;
- rxs->payload.allocated_size = 0U;
- rxs->calculated_crc = CRC_INITIAL;
- rxs->transfer_id = frame->transfer_id;
- rxs->redundant_iface_index = redundant_iface_index;
- rxs->toggle = INITIAL_TOGGLE_STATE;
- }
- else
- {
- out = -CANARD_ERROR_OUT_OF_MEMORY;
+bool canard_v0_respond(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t client_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context)
+{
+ return tx_v0_service(
+ self, deadline, priority, data_type_id, crc_seed, client_node_id, false, transfer_id, payload, user_context);
+}
+
+// --------------------------------------------- RX ---------------------------------------------
+
+typedef struct
+{
+ canard_prio_t priority;
+ canard_kind_t kind;
+
+ uint16_t port_id; // in v0 this stores the data type ID.
+
+ byte_t dst;
+ byte_t src;
+
+ byte_t transfer_id;
+
+ bool start;
+ bool end;
+ bool toggle;
+
+ canard_bytes_t payload;
+} frame_t;
+
+// The protocol version is only unambiguously detectable in the first frame of a transfer.
+// In non-first frames, we attempt to parse the frame as both versions simultaneously and then let the caller
+// decide which one is correct by checking for incomplete multi-frame reassembly states.
+// The return value is a bitmask indicating which of the versions have been parsed at this level.
+// This function admits v0 frames with MTU>8 even though this is not compliant with the v0 specification;
+// there are a few non-compliant implementations out there that use this and there is value in liberal acceptance.
+static byte_t rx_parse(const uint32_t can_id,
+ const canard_bytes_t payload_raw,
+ frame_t* const out_v0,
+ frame_t* const out_v1)
+{
+ CANARD_ASSERT(can_id <= CAN_EXT_ID_MASK);
+ CANARD_ASSERT(out_v0 != NULL);
+ CANARD_ASSERT(out_v1 != NULL);
+ memset(out_v0, 0, sizeof(*out_v0));
+ memset(out_v1, 0, sizeof(*out_v1));
+ if (payload_raw.size < 1) {
+ return 0;
+ }
+ CANARD_ASSERT(payload_raw.data != NULL);
+
+ // Parse the tail byte.
+ const byte_t tail = ((const byte_t*)payload_raw.data)[payload_raw.size - 1U];
+ const bool start = (tail & TAIL_SOT) != 0U;
+ const bool end = (tail & TAIL_EOT) != 0U;
+ const bool toggle = (tail & TAIL_TOGGLE) != 0U;
+ const byte_t transfer_id = tail & CANARD_TRANSFER_ID_MAX;
+
+ // Common items.
+ const canard_prio_t priority = (canard_prio_t)(can_id >> PRIO_SHIFT);
+ const byte_t src = (byte_t)(can_id & CANARD_NODE_ID_MAX);
+
+ // Validate the payload.
+ const canard_bytes_t payload = { .size = payload_raw.size - 1U, .data = payload_raw.data };
+ const bool payload_ok = (end || (payload_raw.size >= CANARD_MTU_CAN_CLASSIC)) && // non-last must use full MTU
+ ((start && end) || (payload.size > 0)); // multi-frame cannot be empty
+
+ // Version detection: v1 requires the toggle to start from 1, v0 starts from 0.
+ // If this is not the first frame of a transfer, the version is not detectable, so we attempt to parse both.
+ bool is_v1 = !(start && !toggle) && payload_ok;
+ bool is_v0 = !(start && toggle) && payload_ok;
+ if (is_v1) {
+ out_v1->priority = priority;
+ out_v1->src = src;
+ out_v1->transfer_id = transfer_id;
+ out_v1->start = start;
+ out_v1->end = end;
+ out_v1->toggle = toggle;
+ out_v1->payload = payload;
+ const bool svc = (can_id & (UINT32_C(1) << 25U)) != 0U;
+ const bool bit_23 = (can_id & (UINT32_C(1) << 23U)) != 0U;
+ if (svc) {
+ out_v1->dst = (byte_t)((can_id >> 7U) & CANARD_NODE_ID_MAX);
+ out_v1->port_id = (can_id >> 14U) & CANARD_SERVICE_ID_MAX;
+ const bool req = (can_id & (UINT32_C(1) << 24U)) != 0U;
+ out_v1->kind = req ? canard_kind_request : canard_kind_response;
+ is_v1 = is_v1 && !bit_23 && (out_v1->src != out_v1->dst); // self-addressing not allowed
+ } else {
+ out_v1->dst = CANARD_NODE_ID_ANONYMOUS;
+ const bool is_1v1 = (can_id & (UINT32_C(1) << 7U)) != 0U;
+ if (is_1v1) {
+ const bool bit_24 = (can_id & (UINT32_C(1) << 24U)) != 0U;
+ is_v1 = is_v1 && !bit_24; // was anonymous
+ out_v1->port_id = (can_id >> 8U) & CANARD_SUBJECT_ID_MAX;
+ out_v1->kind = canard_kind_message_16b;
+ } else {
+ is_v1 = is_v1 && !bit_23;
+ out_v1->port_id = (can_id >> 8U) & CANARD_SUBJECT_ID_MAX_13b;
+ out_v1->kind = canard_kind_message_13b;
+ if ((can_id & (UINT32_C(1) << 24U)) != 0U) {
+ out_v1->src = CANARD_NODE_ID_ANONYMOUS;
+ is_v1 = is_v1 && start && end; // anonymous can only be single-frame
+ }
}
}
- // There are two possible reasons why the session may not exist: 1. OOM; 2. SOT-miss.
- if (subscription->sessions[frame->source_node_id] != NULL)
- {
- CANARD_ASSERT(out == 0);
- out = rxSessionUpdate(ins,
- subscription->sessions[frame->source_node_id],
- frame,
- redundant_iface_index,
- subscription->transfer_id_timeout_usec,
- subscription->extent,
- out_transfer);
- }
}
- else
- {
- CANARD_ASSERT(frame->source_node_id == CANARD_NODE_ID_UNSET);
- // Anonymous transfers are stateless. No need to update the state machine, just blindly accept it.
- // We have to copy the data into an allocated storage because the API expects it: the lifetime shall be
- // independent of the input data and the memory shall be free-able.
- const size_t payload_size =
- (subscription->extent < frame->payload.size) ? subscription->extent : frame->payload.size;
- void* const payload_data = ins->memory.allocate(ins->memory.user_reference, payload_size);
- if (payload_data != NULL)
- {
- rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata);
- out_transfer->timestamp_usec = frame->timestamp_usec;
- out_transfer->payload.size = payload_size;
- out_transfer->payload.data = payload_data;
- out_transfer->payload.allocated_size = payload_size;
- // Clang-Tidy raises an error recommending the use of memcpy_s() instead.
- // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability.
- (void) memcpy(payload_data, frame->payload.data, payload_size); // NOLINT
- out = 1;
- }
- else
- {
- out = -CANARD_ERROR_OUT_OF_MEMORY;
+ if (is_v0) {
+ out_v0->priority = priority;
+ out_v0->src = src;
+ out_v0->transfer_id = transfer_id;
+ out_v0->start = start;
+ out_v0->end = end;
+ out_v0->toggle = toggle;
+ out_v0->payload = payload;
+ const bool svc = (can_id & (UINT32_C(1) << 7U)) != 0U;
+ if (svc) {
+ const byte_t dst = (byte_t)((can_id >> 8U) & CANARD_NODE_ID_MAX);
+ out_v0->dst = dst;
+ out_v0->port_id = (can_id >> 16U) & 0xFFU;
+ const bool req = (can_id & (UINT32_C(1) << 15U)) != 0U;
+ out_v0->kind = req ? canard_kind_v0_request : canard_kind_v0_response;
+ // Node-ID 0 reserved for anonymous/broadcast, invalid for services. Self-addressing not allowed.
+ is_v0 = is_v0 && (dst != 0) && (src != 0) && (src != dst);
+ } else {
+ out_v0->dst = CANARD_NODE_ID_ANONYMOUS;
+ out_v0->port_id = (can_id >> 8U) & 0xFFFFU;
+ out_v0->kind = canard_kind_v0_message;
+ if (src == 0) {
+ out_v0->src = CANARD_NODE_ID_ANONYMOUS;
+ is_v0 = is_v0 && start && end; // anonymous can only be single-frame
+ }
}
}
- return out;
+ return (is_v0 ? 1U : 0U) | (is_v1 ? 2U : 0U);
}
-CANARD_PRIVATE ptrdiff_t
-rxSubscriptionPredicateOnPortID(const void* const user_reference, // NOSONAR Cavl API requires pointer to non-const.
- const struct CanardTreeNode* const node)
+// Idle sessions are removed after this timeout even if reassembly is not finished.
+// This is not related to the transfer-ID timeout and does not affect the correctness;
+// it is only needed to improve the memory footprint when remotes cease sending messages.
+// This could be made configurable but it is not a tuning-sensitive parameter.
+#define RX_SESSION_TIMEOUT (30 * MEGA)
+
+// Reassembly state at a specific priority level.
+// Maintaining separate state per priority level allows preemption of higher-priority transfers without loss.
+// Interface affinity is required because frames duplicated across redundant interfaces may arrive with a significant
+// delay, which may cause the receiver to accept more frames than necessary.
+typedef struct
{
- CANARD_ASSERT((user_reference != NULL) && (node != NULL));
- const CanardPortID sought = *((const CanardPortID*) user_reference);
- const CanardPortID other = CAVL2_TO_OWNER(node, struct CanardRxSubscription, base)->port_id;
- static const int8_t NegPos[2] = {-1, +1};
- // Clang-Tidy mistakenly identifies a narrowing cast to int8_t here, which is incorrect.
- return (sought == other) ? 0 : NegPos[sought > other]; // NOLINT no narrowing conversion is taking place here
+ canard_us_t start_ts;
+ uint32_t total_size; // The raw payload size seen before the implicit truncation and CRC removal.
+ uint16_t crc;
+ byte_t transfer_id : CANARD_TRANSFER_ID_BITS;
+ byte_t iface_index : IFACE_INDEX_BITS;
+ byte_t expected_toggle : 1;
+ byte_t payload[]; // Extent-sized.
+} rx_slot_t;
+#define RX_SLOT_OVERHEAD (offsetof(rx_slot_t, payload))
+static_assert(RX_SLOT_OVERHEAD <= 16, "unexpected layout");
+
+static rx_slot_t* rx_slot_new(const canard_subscription_t* const sub,
+ const canard_us_t start_ts,
+ const byte_t transfer_id,
+ const byte_t iface_index)
+{
+ rx_slot_t* const slot = mem_alloc(sub->owner->mem.rx_payload, RX_SLOT_OVERHEAD + sub->extent);
+ if (slot != NULL) {
+ memset(slot, 0, RX_SLOT_OVERHEAD);
+ slot->start_ts = start_ts;
+ slot->crc = sub->crc_seed;
+ slot->transfer_id = transfer_id & CANARD_TRANSFER_ID_MAX;
+ slot->expected_toggle = canard_kind_version(sub->kind) & 1U;
+ slot->iface_index = iface_index & ((1U << IFACE_INDEX_BITS) - 1U);
+ }
+ return slot;
}
-CANARD_PRIVATE ptrdiff_t
-rxSubscriptionPredicateOnStruct(const void* const user_reference, // NOSONAR Cavl API requires pointer to non-const.
- const struct CanardTreeNode* const node)
+static void rx_slot_destroy(const canard_subscription_t* const sub, rx_slot_t* const slot)
{
- return rxSubscriptionPredicateOnPortID( //
- &CAVL2_TO_OWNER(user_reference, struct CanardRxSubscription, base)->port_id,
- node);
+ mem_free(sub->owner->mem.rx_payload, RX_SLOT_OVERHEAD + sub->extent, slot);
}
-// --------------------------------------------- PUBLIC API ---------------------------------------------
-
-const uint8_t CanardCANDLCToLength[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64};
-const uint8_t CanardCANLengthToDLC[65] = {
- 0, 1, 2, 3, 4, 5, 6, 7, 8, // 0-8
- 9, 9, 9, 9, // 9-12
- 10, 10, 10, 10, // 13-16
- 11, 11, 11, 11, // 17-20
- 12, 12, 12, 12, // 21-24
- 13, 13, 13, 13, 13, 13, 13, 13, // 25-32
- 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, // 33-48
- 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, // 49-64
-};
+static void rx_slot_advance(rx_slot_t* const slot, const size_t extent, const canard_bytes_t payload)
+{
+ if (slot->total_size < extent) {
+ const size_t copy_size = smaller(payload.size, (size_t)(extent - slot->total_size)); // NOLINT(*-casting)
+ (void)memcpy(&slot->payload[slot->total_size], payload.data, copy_size);
+ }
+ slot->total_size = (uint32_t)(slot->total_size + payload.size); // Before truncation.
+ slot->expected_toggle ^= 1U;
+}
-struct CanardInstance canardInit(const struct CanardMemoryResource memory)
+// Up to libcanard v4 we used a fixed-capacity array of pointers for per-remote sessions for constant-time lookup,
+// but it was too costly on MCUs: with a 32-bit pointer it took 512 bytes for the array plus overheads,
+// resulting in 1 KiB o1heap blocks per session, very expensive. Here we use a much less RAM-heavy approach with
+// sparse nodes in a tree with log-time lookup.
+//
+// Design goals:
+//
+// - Admit frames from a single interface only, arbitrarily chosen, until it has been observed to be silent for
+// at least one transfer-ID timeout period. This is because redundant interfaces may carry frames with a significant
+// delay, which may cause a receiver to admit the same transfer multiple times without interface affinity.
+//
+// - Allow preemption of transfers by higher-priority ones, without loss of the preempted transfer's state.
+//
+// - The case of a zero transfer-ID timeout is a first-class use case. In this mode, duplication is tolerated by
+// the application, but multi-frame transfers must still follow interface affinity to avoid incorrect reassembly.
+//
+// Assumptions:
+// - Frames within a transfer arrive in order;
+// see https://forum.opencyphal.org/t/uavcan-can-tx-buffer-management-in-can-fd-controllers/1215
+// - A frame may be duplicated (a well-known CAN PHY edge case), but duplicates immediately follow the original.
+//
+// Core invariants:
+// - Only start-of-transfer may create/replace a slot.
+// - Non-start frames never create state.
+// - Session dedup state is updated on admitted start-of-transfer, not on transfer completion.
+// - Timeout is consulted only for start-of-transfer admission.
+// - Slot matching for continuation uses exact match: priority, transfer-ID/seqno, toggle, and iface.
+typedef struct
{
- CANARD_ASSERT(memory.allocate != NULL);
- CANARD_ASSERT(memory.deallocate != NULL);
- const struct CanardInstance out = {
- .user_reference = NULL,
- .node_id = CANARD_NODE_ID_UNSET,
- .memory = memory,
- .rx_subscriptions = {NULL, NULL, NULL},
- };
- return out;
+ canard_tree_t index;
+ canard_listed_t list_animation; // On update, session moved to the tail; oldest pushed to the head.
+ canard_us_t last_admission_ts;
+ rx_slot_t* slots[CANARD_PRIO_COUNT]; // Indexed by priority level to allow preemption.
+ canard_subscription_t* owner;
+ byte_t node_id;
+ byte_t last_admitted_transfer_id;
+ byte_t last_admitted_priority;
+ byte_t iface_index;
+} rx_session_t;
+static_assert((sizeof(void*) > 4) || (sizeof(rx_session_t) <= 120), "too large");
+
+static int32_t rx_session_cavl_compare(const void* const user, const canard_tree_t* const node)
+{
+ return ((int32_t)(*(byte_t*)user)) - ((int32_t)CAVL2_TO_OWNER(node, rx_session_t, index)->node_id);
}
-struct CanardTxQueue canardTxInit(const size_t capacity,
- const size_t mtu_bytes,
- const struct CanardMemoryResource memory)
-{
- CANARD_ASSERT(memory.allocate != NULL);
- CANARD_ASSERT(memory.deallocate != NULL);
- struct CanardTxQueue out = {
- .capacity = capacity,
- .mtu_bytes = mtu_bytes,
- .size = 0,
- .priority_root = NULL,
- .deadline_root = NULL,
- .memory = memory,
- .user_reference = NULL,
- };
- return out;
+typedef struct
+{
+ canard_subscription_t* owner;
+ byte_t iface_index; // Start with the affinity to the iface that delivered the first frame.
+ byte_t node_id;
+} rx_session_factory_context_t;
+
+static canard_tree_t* rx_session_factory(void* const user)
+{
+ const rx_session_factory_context_t* const ctx = (rx_session_factory_context_t*)user;
+ rx_session_t* const ses = mem_alloc_zero(ctx->owner->owner->mem.rx_session, sizeof(rx_session_t));
+ if (ses == NULL) {
+ return NULL;
+ }
+ FOREACH_PRIO (i) {
+ ses->slots[i] = NULL;
+ }
+ ses->last_admission_ts = BIG_BANG;
+ ses->owner = ctx->owner;
+ ses->iface_index = ctx->iface_index;
+ ses->node_id = ctx->node_id;
+ enlist_tail(&ctx->owner->owner->rx.list_session_by_animation, &ses->list_animation);
+ return &ses->index;
}
-int32_t canardTxPush(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond tx_deadline_usec,
- const struct CanardTransferMetadata* const metadata,
- const struct CanardPayload payload,
- const CanardMicrosecond now_usec,
- uint64_t* const frames_expired)
+static void rx_session_destroy(rx_session_t* const ses)
{
- // Before pushing payload (potentially in multiple frames), we need to try to flush any expired transfers.
- // This is necessary to ensure that we don't exhaust the capacity of the queue by holding outdated frames.
- // The flushing is done by comparing deadline timestamps of the pending transfers with the current time,
- // which makes sense only if the current time is known (bigger than zero).
- if (now_usec > 0)
- {
- const size_t count = txFlushExpiredTransfers(que, ins, now_usec);
- if (frames_expired != NULL)
- {
- (*frames_expired) += count;
- }
+ canard_subscription_t* const sub = ses->owner;
+ FOREACH_PRIO (i) {
+ rx_slot_destroy(sub, ses->slots[i]);
}
+ CANARD_ASSERT(cavl2_is_inserted(sub->sessions, &ses->index));
+ cavl2_remove(&sub->sessions, &ses->index);
+ delist(&sub->owner->rx.list_session_by_animation, &ses->list_animation);
+ mem_free(sub->owner->mem.rx_session, sizeof(rx_session_t), ses);
+}
- int32_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- if ((ins != NULL) && (que != NULL) && (metadata != NULL) && ((payload.data != NULL) || (0U == payload.size)))
- {
- const size_t pl_mtu = adjustPresentationLayerMTU(que->mtu_bytes);
- const int32_t maybe_can_id = txMakeCANID(metadata, payload, ins->node_id, pl_mtu);
- if (maybe_can_id >= 0)
- {
- if (payload.size <= pl_mtu)
- {
- out = txPushSingleFrame(que,
- ins,
- tx_deadline_usec,
- (uint32_t) maybe_can_id,
- metadata->transfer_id,
- payload);
- CANARD_ASSERT((out < 0) || (out == 1));
- }
- else
- {
- out = txPushMultiFrame(que,
- ins,
- pl_mtu,
- tx_deadline_usec,
- (uint32_t) maybe_can_id,
- metadata->transfer_id,
- payload);
- CANARD_ASSERT((out < 0) || (out >= 2));
- }
+// Checks the state and purges stale slots to reclaim memory early. Returns the number of in-progress slots remaining.
+static size_t rx_session_cleanup(rx_session_t* const ses, const canard_us_t now)
+{
+ const canard_us_t deadline = now - later(RX_SESSION_TIMEOUT, ses->owner->transfer_id_timeout);
+ size_t n_slots = 0;
+ FOREACH_PRIO (i) {
+ const rx_slot_t* const slot = ses->slots[i];
+ if (slot == NULL) {
+ continue;
}
- else
- {
- out = maybe_can_id;
+ CANARD_ASSERT((0 <= slot->start_ts) && (slot->start_ts <= ses->last_admission_ts));
+ if (slot->start_ts < deadline) { // Too old, destroy even if in progress -- unlikely to complete anyway.
+ rx_slot_destroy(ses->owner, ses->slots[i]);
+ ses->slots[i] = NULL;
+ } else {
+ n_slots++;
}
}
- CANARD_ASSERT(out != 0);
- return out;
+ return n_slots;
}
-struct CanardTxQueueItem* canardTxPeek(const struct CanardTxQueue* const que)
+static void rx_session_complete_single_frame(canard_subscription_t* const sub,
+ const canard_us_t ts,
+ const frame_t* const fr)
{
- struct CanardTxQueueItem* out = NULL;
- if (que != NULL)
- {
- struct CanardTreeNode* const priority_node = cavl2_min(que->priority_root);
- out = CAVL2_TO_OWNER(priority_node, struct CanardTxQueueItem, priority_base);
- }
- return out;
+ CANARD_ASSERT(fr->start && fr->end && (fr->port_id == sub->port_id) && (fr->kind == sub->kind));
+ CANARD_ASSERT(sub->vtable->on_message != NULL);
+ const canard_payload_t payload = { .view = fr->payload, .origin = { .data = NULL, .size = 0 } };
+ sub->vtable->on_message(sub, ts, fr->priority, fr->src, fr->transfer_id, payload);
}
-struct CanardTxQueueItem* canardTxPop(struct CanardTxQueue* const que, struct CanardTxQueueItem* const item)
+static void rx_session_complete_slot(rx_session_t* const ses, const frame_t* const fr)
{
- if ((que != NULL) && (item != NULL))
- {
- // Paragraph 6.7.2.1.15 of the C standard says:
- // A pointer to a structure object, suitably converted, points to its initial member, and vice versa.
- // Note that the highest-priority frame is always a leaf node in the AVL tree, which means that it is very
- // cheap to remove.
- cavl2_remove(&que->priority_root, &item->priority_base);
- cavl2_remove(&que->deadline_root, &item->deadline_base);
- que->size--;
+ canard_subscription_t* const sub = ses->owner;
+ rx_slot_t* const slot = ses->slots[fr->priority];
+ CANARD_ASSERT(!fr->start && fr->end && (fr->port_id == sub->port_id) && (fr->kind == sub->kind));
+ CANARD_ASSERT((slot != NULL) && (sub->vtable->on_message != NULL));
+ CANARD_ASSERT((slot->transfer_id == fr->transfer_id) && (slot->iface_index == ses->iface_index));
+ CANARD_ASSERT(fr->src != CANARD_NODE_ID_ANONYMOUS); // anons cannot be multiframe
+ // Verify the CRC and dispatch the message if correct. The slot is consumed in either case.
+ ses->slots[fr->priority] = NULL; // Slot memory ownership transferred to the application, or destroyed.
+ const bool v1 = canard_kind_version(sub->kind) == 1;
+ const uint16_t crc_ref = v1 ? CRC_RESIDUE : (uint16_t)(slot->payload[0] | (((unsigned)slot->payload[1]) << 8U));
+ CANARD_ASSERT(v1 || (sub->extent >= CRC_BYTES)); // In v0, the CRC size is included in the extent.
+ if (slot->crc == crc_ref) {
+ const size_t size = smaller(slot->total_size - CRC_BYTES, sub->extent - (v1 ? 0 : CRC_BYTES));
+ const canard_payload_t payload = {
+ .view = { .data = v1 ? slot->payload : &slot->payload[CRC_BYTES], .size = size },
+ .origin = { .data = slot, .size = RX_SLOT_OVERHEAD + sub->extent },
+ };
+ sub->vtable->on_message(sub, slot->start_ts, fr->priority, fr->src, fr->transfer_id, payload);
+ } else {
+ sub->owner->err.rx_transfer++;
+ rx_slot_destroy(ses->owner, slot);
}
- return item;
}
-void canardTxFree(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- struct CanardTxQueueItem* item)
+static void rx_session_accept(rx_session_t* const ses, const canard_us_t ts_frame, const frame_t* const fr)
{
- if ((que != NULL) && (ins != NULL) && (item != NULL))
- {
- if (item->frame.payload.data != NULL)
- {
- que->memory.deallocate(que->memory.user_reference,
- item->frame.payload.allocated_size,
- item->frame.payload.data);
+ canard_subscription_t* const sub = ses->owner;
+ CANARD_ASSERT((fr->port_id == sub->port_id) && (fr->kind == sub->kind));
+ rx_slot_t* const slot = ses->slots[fr->priority];
+ if (slot != NULL) {
+ CANARD_ASSERT((!fr->start || !fr->end) && (slot->expected_toggle == fr->toggle));
+ CANARD_ASSERT((slot->transfer_id == fr->transfer_id) && (slot->iface_index == ses->iface_index));
+ rx_slot_advance(slot, sub->extent, fr->payload);
+ // Multi-frame transfers place CRC differently in v1 and v0.
+ // The v1 handling is trivial: simply compute the full payload CRC and ensure the residue is correct.
+ // The payload may be truncated to the subscription extent, but the CRC is computed over the full payload.
+ // Legacy v0 is messy because the CRC is in the beginning, which we need to handle specially.
+ // The CRC initial state is constant for v1, data-type-dependent for v0; this is managed outside of this scope.
+ const canard_bytes_t crc_input =
+ ((canard_kind_version(sub->kind) == 0) && fr->start)
+ ? (canard_bytes_t){ .size = fr->payload.size - CRC_BYTES, .data = ((byte_t*)fr->payload.data) + CRC_BYTES }
+ : fr->payload;
+ slot->crc = crc_add(slot->crc, crc_input.size, crc_input.data);
+ if (fr->end) {
+ rx_session_complete_slot(ses, fr);
}
+ } else {
+ CANARD_ASSERT(fr->start && fr->end);
+ rx_session_complete_single_frame(sub, ts_frame, fr);
+ }
+}
- ins->memory.deallocate(ins->memory.user_reference, sizeof(struct CanardTxQueueItem), item);
+static void rx_session_record_admission(rx_session_t* const ses,
+ const canard_prio_t priority,
+ const byte_t transfer_id,
+ const canard_us_t ts,
+ const byte_t iface_index)
+{
+ ses->last_admission_ts = ts;
+ ses->last_admitted_transfer_id = transfer_id & CANARD_TRANSFER_ID_MAX;
+ ses->last_admitted_priority = ((byte_t)priority) & ((1U << CANARD_PRIO_BITS) - 1U);
+ ses->iface_index = iface_index & ((1U << IFACE_INDEX_BITS) - 1U);
+}
+
+// Frame admittance solver. A complex piece, redesigned after v4 to support priority preemption & parallel reassembly.
+static bool rx_session_solve_admission(const rx_session_t* const ses,
+ const canard_us_t ts,
+ const canard_prio_t priority,
+ const bool start,
+ const bool toggle,
+ const byte_t transfer_id,
+ const byte_t iface_index)
+{
+ // Continuation frames cannot create new state so their handling is simpler.
+ // They are only accepted if there is a slot with an exact match of all transfer parameters.
+ // We ignore the transfer-ID timeout to avoid breaking transfers that are preempted for a long time,
+ // and especially to allow reassembly of multi-frame transfers even when the transfer-ID timeout is zero.
+ if (!start) {
+ const rx_slot_t* const slot = ses->slots[priority];
+ return (slot != NULL) && (slot->transfer_id == transfer_id) && (slot->iface_index == iface_index) &&
+ (slot->expected_toggle == toggle);
}
+ // Duplicate start frames do not require special treatment because a duplicate frame can only follow the original
+ // without any frames belonging to the same transfer in between (see the assumptions). If we get a duplicate start,
+ // with a nonzero TID timeout it will be rejected as not-new. Zero transfer-ID timeout means the application
+ // accepts duplicates; with zero timeout duplicate rejection is not possible given this protocol design.
+ //
+ // The original design had a special case that enabled admittance of a transfer with the next transfer-ID from a
+ // different interface if there is no pending reassembly in progress; see details here and the original v4 code:
+ // https://github.com/OpenCyphal/libcanard/issues/228. This behavior is no longer present here mostly because we
+ // now update the session state only on admittance and not upon completion of a transfer, which changes the logic
+ // considerably. One side effect is that even after a timeout (potentially a very long time as long as the session
+ // survives) we will still reject a new transfer arriving from a different interface if it happened to roll the
+ // same transfer-ID. This is not an issue because we would still accept new transfers on the same iface,
+ // and after the RX_SESSION_TIMEOUT the session is destroyed and all new transfers will be accepted unconditionally.
+ //
+ // Merely comparing against the last admitted transfer-ID is not enough because there is a preemption-related edge
+ // case. Suppose the transfer-ID modulo is 4, i.e., the values are {0, 1, 2, 3}; a low-priority transfer is sent
+ // but preempted by higher-priority peers before it hits the bus as illustrated below.
+ //
+ // |SENDER |
+ // P=low |0 |
+ // P=high | 1 2 3 0 | <-- preempt the low-priority frame
+ //
+ // |RECEIVER |
+ // P=low | 0 | <-- arrived late, rejected as duplicate!
+ // P=high | 1 2 3 0 |
+ //
+ // One solution is to track the last admitted priority along with the transfer-ID:
+ // preemption alters the admitted priority, which prevents false rejection.
+ //
+ // There is one critical edge case: if a low-priority frame is duplicated (due to the CAN ACK glitch effect)
+ // AND at least one higher-priority frame is admitted between the original frame and its duplicate,
+ // then the duplicate will be accepted as a new transfer.
+ // Example: low-prio tid=1, high-prio preemption tid=2, high-prio tid=2...X, low-prio duplicate tid=1.
+ // In general, the problem of duplicate detection under these conditions is believed to be undecidable.
+ // We inherit the CAN PHY design limitation here by accepting the risk of spurious duplication, recognizing that
+ // it is very low, as it requires both unlikely events to occur simultaneously: CAN ACK glitch and a high-priority
+ // preemption exactly between the original transmission and its duplicate.
+ const bool fresh = (transfer_id != ses->last_admitted_transfer_id) || // always accept if transfer-ID is different
+ (priority != ses->last_admitted_priority); // or we switched the priority level
+ const bool affine = ses->iface_index == iface_index;
+ const bool stale = (ts - ses->owner->transfer_id_timeout) > ses->last_admission_ts;
+ return (fresh && affine) || (affine && stale) || (stale && fresh);
}
-int8_t canardTxPoll(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond now_usec,
- void* const user_reference,
- const CanardTxFrameHandler frame_handler,
- uint64_t* const frames_expired,
- uint64_t* const frames_failed)
+// The caller must ensure the frame is of the correct version that matches the subscription (v0/v1).
+// The caller must ensure the frame is directed to the local node (broadcast or unicast to the local node-ID).
+static void rx_session_update(canard_subscription_t* const sub,
+ const canard_us_t ts,
+ const frame_t* const frame,
+ const byte_t iface_index)
{
- int8_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- if ((que != NULL) && (ins != NULL) && (frame_handler != NULL))
- {
- // Before peeking a frame to transmit, we need to try to flush any expired transfers.
- // This will not only ensure ASAP freeing of the queue capacity, but also makes sure that the following
- // `canardTxPeek` will return a not expired item (if any), so we don't need to check the deadline again.
- // The flushing is done by comparing deadline timestamps of the pending transfers with the current time,
- // which makes sense only if the current time is known (bigger than zero).
- if (now_usec > 0)
- {
- const size_t count = txFlushExpiredTransfers(que, ins, now_usec);
- if (frames_expired != NULL)
- {
- (*frames_expired) += count;
- }
- }
+ CANARD_ASSERT((sub != NULL) && (frame != NULL) && (frame->payload.data != NULL) && (ts >= 0));
+ CANARD_ASSERT(frame->end || (frame->payload.size >= 7));
+ CANARD_ASSERT(!frame->start || (frame->toggle == canard_kind_version(sub->kind)));
+ CANARD_ASSERT((frame->dst == CANARD_NODE_ID_ANONYMOUS) || (frame->dst == sub->owner->node_id));
+ CANARD_ASSERT((canard_kind_version(sub->kind) != 0) || (sub->extent >= CRC_BYTES)); // v0 CRC reservation
+
+ // Anonymous frames are stateless and require special treatment.
+ // They are scheduled to be deprecated in Cyphal v1.1.
+ if (frame->src == CANARD_NODE_ID_ANONYMOUS) {
+ CANARD_ASSERT(frame->start && frame->end && (frame->dst == CANARD_NODE_ID_ANONYMOUS));
+ CANARD_ASSERT((frame->kind == canard_kind_v0_message) || (frame->kind == canard_kind_message_13b));
+ rx_session_complete_single_frame(sub, ts, frame);
+ return;
+ }
- struct CanardTxQueueItem* const tx_item = canardTxPeek(que);
- if (tx_item != NULL)
- {
- // No need to check the deadline again, as we have already flushed all expired transfers.
- out = frame_handler(user_reference, tx_item->tx_deadline_usec, &tx_item->frame);
- // We gonna release (pop and free) the frame if the handler returned:
- // - either a positive value - the frame has been successfully accepted by the handler;
- // - or a negative value - the frame has been rejected by the handler due to a failure.
- // Zero value means that the handler cannot accept the frame at the moment, so we keep it in the queue.
- if (out != 0)
- {
- const bool failed = out < 0;
- const size_t count = txPopAndFreeTransfer(que, ins, tx_item, failed);
- if (failed && (frames_failed != NULL))
- {
- (*frames_failed) += count;
- }
- }
+ // Only start frames may create new states.
+ // The protocol version is observable on start frames by design, which makes this robust.
+ // At this point we also ensured the frame is not misaddressed.
+ rx_session_factory_context_t factory_context = { .owner = sub, .iface_index = iface_index, .node_id = frame->src };
+ rx_session_t* const ses =
+ CAVL2_TO_OWNER(frame->start ? cavl2_find_or_insert(&sub->sessions, //
+ &frame->src,
+ rx_session_cavl_compare,
+ &factory_context,
+ rx_session_factory)
+ : cavl2_find(sub->sessions, &frame->src, rx_session_cavl_compare),
+ rx_session_t,
+ index);
+ if (ses == NULL) {
+ sub->owner->err.oom += frame->start;
+ return;
+ }
+
+ // Decide admit or drop.
+ const bool admit = rx_session_solve_admission(
+ ses, ts, frame->priority, frame->start, frame->toggle, frame->transfer_id, iface_index);
+ if (!admit) {
+ return;
+ }
+
+ // The frame must be accepted. If this is the start of a new transfer, we must update state.
+ if (frame->start) {
+ // Animate only when a new transfer is started to manage load. Correctness-wise there is not much difference.
+ enlist_tail(&sub->owner->rx.list_session_by_animation, &ses->list_animation);
+ // Destroy the old slot if it exists, meaning we're discarding stale transfer.
+ if (ses->slots[frame->priority] != NULL) {
+ rx_slot_destroy(sub, ses->slots[frame->priority]);
+ ses->slots[frame->priority] = NULL;
}
- else
- {
- out = 0; // No frames to transmit.
+ // If there are more frames to follow, we must store in-progress state for reassembly.
+ if (!frame->end) {
+ (void)rx_session_cleanup(ses, ts); // Cleanup before allocating a new slot; don't do too often, is costly.
+ ses->slots[frame->priority] = rx_slot_new(sub, ts, frame->transfer_id, iface_index);
+ if (ses->slots[frame->priority] == NULL) {
+ sub->owner->err.oom++;
+ return;
+ }
+ CANARD_ASSERT(ses->slots[frame->priority]->transfer_id == frame->transfer_id);
+ CANARD_ASSERT(ses->slots[frame->priority]->expected_toggle == frame->toggle);
}
+ // Register the new state only after we have a confirmation that we have memory to store the frame.
+ rx_session_record_admission(ses, frame->priority, frame->transfer_id, ts, iface_index);
}
- CANARD_ASSERT(out <= 1);
- return out;
+ // Accept the frame.
+ rx_session_accept(ses, ts, frame);
+ CANARD_ASSERT(!frame->end || (ses->slots[frame->priority] == NULL));
}
-int8_t canardRxAccept(struct CanardInstance* const ins,
- const CanardMicrosecond timestamp_usec,
- const struct CanardFrame* const frame,
- const uint8_t redundant_iface_index,
- struct CanardRxTransfer* const out_transfer,
- struct CanardRxSubscription** const out_subscription)
+static int32_t rx_subscription_cavl_compare(const void* const user, const canard_tree_t* const node)
{
- int8_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- if ((ins != NULL) && (out_transfer != NULL) && (frame != NULL) && (frame->extended_can_id <= CAN_EXT_ID_MASK) &&
- ((frame->payload.data != NULL) || (0 == frame->payload.size)))
- {
- RxFrameModel model = {0};
- if (rxTryParseFrame(timestamp_usec, frame, &model))
- {
- if ((CANARD_NODE_ID_UNSET == model.destination_node_id) || (ins->node_id == model.destination_node_id))
- {
- // This is the reason the function has a logarithmic time complexity of the number of subscriptions.
- // Note also that this one of the two variable-complexity operations in the RX pipeline; the other one
- // is memcpy(). Excepting these two cases, the entire RX pipeline contains neither loops nor recursion.
- struct CanardTreeNode* const sub_node = cavl2_find(ins->rx_subscriptions[(size_t) model.transfer_kind],
- &model.port_id,
- &rxSubscriptionPredicateOnPortID);
- struct CanardRxSubscription* const sub = CAVL2_TO_OWNER(sub_node, struct CanardRxSubscription, base);
- if (out_subscription != NULL)
- {
- *out_subscription = sub; // Expose selected instance to the caller.
- }
- if (sub != NULL)
- {
- CANARD_ASSERT(sub->port_id == model.port_id);
- out = rxAcceptFrame(ins, sub, &model, redundant_iface_index, out_transfer);
- }
- else
- {
- out = 0; // No matching subscription.
- }
- }
- else
- {
- out = 0; // Mis-addressed frame (normally it should be filtered out by the hardware).
- }
+ return ((int32_t)(*(const uint16_t*)user)) - ((int32_t)((const canard_subscription_t*)(const void*)node)->port_id);
+}
+
+// Locates the appropriate subscription if the destination is matching and there is a subscription.
+static canard_subscription_t* rx_route(const canard_t* const self, const frame_t* const fr)
+{
+ CANARD_ASSERT((self != NULL) && (fr != NULL));
+ if ((fr->dst != CANARD_NODE_ID_ANONYMOUS) && (fr->dst != self->node_id)) {
+ return NULL; // misfiltered
+ }
+ return (canard_subscription_t*)(void*)cavl2_find(
+ self->rx.subscriptions[fr->kind], &fr->port_id, rx_subscription_cavl_compare);
+}
+
+// Builds an acceptance filter that only admits frames matching the given kind and port-ID.
+static canard_filter_t rx_filter_for_subscription(const canard_t* const self,
+ const canard_kind_t kind,
+ const uint16_t port_id)
+{
+ CANARD_ASSERT(self != NULL);
+ canard_filter_t f = { 0 };
+ const uint32_t id = self->node_id & CANARD_NODE_ID_MAX;
+ switch (kind) {
+ case canard_kind_message_16b:
+ f.extended_can_id = ((uint32_t)port_id << 8U) | (UINT32_C(1) << 7U);
+ f.extended_mask = 0x03FFFF80U;
+ break;
+ case canard_kind_message_13b:
+ CANARD_ASSERT(port_id <= CANARD_SUBJECT_ID_MAX_13b);
+ f.extended_can_id = (uint32_t)port_id << 8U;
+ f.extended_mask = 0x029fff80U;
+ break;
+ case canard_kind_response:
+ case canard_kind_request: {
+ CANARD_ASSERT(port_id <= CANARD_SERVICE_ID_MAX);
+ const uint32_t rnr = (kind == canard_kind_request) ? (UINT32_C(1) << 24U) : 0U;
+ f.extended_can_id = (UINT32_C(1) << 25U) | rnr | ((uint32_t)port_id << 14U) | (id << 7U);
+ f.extended_mask = 0x03FFFF80U;
+ break;
}
- else
- {
- out = 0; // A non-Cyphal/CAN input frame.
+ case canard_kind_v0_message:
+ f.extended_can_id = (uint32_t)port_id << 8U;
+ f.extended_mask = 0x00FFFF80;
+ break;
+ case canard_kind_v0_response:
+ case canard_kind_v0_request: {
+ CANARD_ASSERT(port_id <= 0xFFU);
+ const uint32_t rnr = (kind == canard_kind_v0_request) ? (UINT32_C(1) << 15U) : 0;
+ f.extended_can_id = ((port_id & 0xFFU) << 16U) | rnr | (id << 8U) | (UINT32_C(1) << 7U);
+ f.extended_mask = 0x00FFFF80U;
+ break;
}
+ default:
+ CANARD_ASSERT(false);
}
- CANARD_ASSERT(out <= 1);
- return out;
+ return f;
}
-int8_t canardRxSubscribe(struct CanardInstance* const ins,
- const enum CanardTransferKind transfer_kind,
- const CanardPortID port_id,
- const size_t extent,
- const CanardMicrosecond transfer_id_timeout_usec,
- struct CanardRxSubscription* const out_subscription)
+// Make a new filter that will accept frames accepted by either of the arguments (minimal superset).
+static canard_filter_t rx_filter_fuse(const canard_filter_t a, const canard_filter_t b)
{
- int8_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- const size_t tk = (size_t) transfer_kind;
- const bool port_id_ok = ((transfer_kind == CanardTransferKindMessage) && (port_id <= CANARD_SUBJECT_ID_MAX)) ||
- (port_id <= CANARD_SERVICE_ID_MAX);
- if ((ins != NULL) && (out_subscription != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS) && port_id_ok)
- {
- // Reset to the initial state. This is absolutely critical because the new payload size limit may be larger
- // than the old value; if there are any payload buffers allocated, we may overrun them because they are shorter
- // than the new payload limit. So we clear the subscription and thus ensure that no overrun may occur.
- out = canardRxUnsubscribe(ins, transfer_kind, port_id);
- if (out >= 0)
- {
- out_subscription->transfer_id_timeout_usec = transfer_id_timeout_usec;
- out_subscription->extent = extent;
- out_subscription->port_id = port_id;
- for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++)
- {
- // The sessions will be created ad-hoc. Normally, for a low-jitter deterministic system,
- // we could have pre-allocated sessions here, but that requires too much memory to be feasible.
- // We could accept an extra argument that would instruct us to pre-allocate sessions here?
- out_subscription->sessions[i] = NULL;
- }
- const struct CanardTreeNode* const res = cavl2_find_or_insert(&ins->rx_subscriptions[tk],
- &out_subscription->base,
- &rxSubscriptionPredicateOnStruct,
- &out_subscription->base,
- &cavl2_trivial_factory);
- (void) res;
- CANARD_ASSERT(res == &out_subscription->base);
- out = (out > 0) ? 0 : 1;
+ const uint32_t mask = a.extended_mask & b.extended_mask & ~(a.extended_can_id ^ b.extended_can_id);
+ return (canard_filter_t){ .extended_can_id = a.extended_can_id & mask, .extended_mask = mask };
+}
+
+// Filter selectivity metric; see the Cyphal/CAN specification. Greater values ==> stronger filter.
+static byte_t rx_filter_rank(const canard_filter_t a) { return popcount(a.extended_mask); }
+
+// Returns true if any filter in the array accepts the given extended CAN ID.
+static bool rx_filter_match(const size_t count, const canard_filter_t* const filters, const uint32_t extended_can_id)
+{
+ for (size_t i = 0; i < count; i++) {
+ if ((extended_can_id & filters[i].extended_mask) == (filters[i].extended_can_id & filters[i].extended_mask)) {
+ return true;
}
}
- return out;
+ return false;
}
-int8_t canardRxUnsubscribe(struct CanardInstance* const ins,
- const enum CanardTransferKind transfer_kind,
- const CanardPortID port_id)
+// Modifies the filter array such that the new filter is accepted. See Cyphal/CAN Spec. Requires count>0.
+static void rx_filter_coalesce_into(const size_t count, canard_filter_t* const into, const canard_filter_t new)
{
- int8_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- const size_t tk = (size_t) transfer_kind;
- if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS))
- {
- CanardPortID port_id_mutable = port_id;
-
- struct CanardTreeNode* const sub_node =
- cavl2_find(ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID);
- if (sub_node != NULL)
- {
- struct CanardRxSubscription* const sub = CAVL2_TO_OWNER(sub_node, struct CanardRxSubscription, base);
- cavl2_remove(&ins->rx_subscriptions[tk], sub_node);
- CANARD_ASSERT(sub->port_id == port_id);
- out = 1;
- for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++)
- {
- CanardInternalRxSession* const session = sub->sessions[i];
- if (session != NULL)
- {
- ins->memory.deallocate(ins->memory.user_reference,
- session->payload.allocated_size,
- session->payload.data);
- ins->memory.deallocate(ins->memory.user_reference, sizeof(*session), session);
- sub->sessions[i] = NULL;
- }
+ CANARD_ASSERT((count > 0U) && (into != NULL));
+ // Find the most similar pair by trying all pair combinations (including the incoming filter).
+ // This is O(N^2) but yields better final filter quality than fusing only with the incoming filter.
+ // The complexity is acceptable because N is controlled by the application and is small;
+ // plus, this behavior can be disabled completely by using at least as many filters as there are subscriptions.
+ bool initialized = false;
+ size_t best_i = 0;
+ size_t best_j = count;
+ byte_t best_rank = 0;
+ canard_filter_t best_fuse = { 0 };
+ for (size_t i = 0; i < count; i++) {
+ for (size_t j = i + 1U; j <= count; j++) { // j==count denotes the incoming filter
+ const canard_filter_t f = rx_filter_fuse(into[i], (j < count) ? into[j] : new);
+ const byte_t r = rx_filter_rank(f);
+ if ((!initialized) || (r >= best_rank)) { // use >= to prefer later filters where v0 is
+ initialized = true;
+ best_i = i;
+ best_j = j;
+ best_rank = r;
+ best_fuse = f;
}
}
- else
- {
- out = 0;
- }
}
- return out;
+ CANARD_ASSERT(initialized && (best_i < count) && (best_j <= count));
+ into[best_i] = best_fuse;
+ if (best_j < count) {
+ into[best_j] = new;
+ }
}
-int8_t canardRxGetSubscription(const struct CanardInstance* const ins,
- const enum CanardTransferKind transfer_kind,
- const CanardPortID port_id,
- struct CanardRxSubscription** const out_subscription)
+// Recompute the filter configuration and apply. Returns true on success, false on driver error.
+static bool rx_filter_configure(canard_t* const self)
{
- int8_t out = -CANARD_ERROR_INVALID_ARGUMENT;
- const size_t tk = (size_t) transfer_kind;
- if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS))
+ if (self->rx.filter_count == 0) {
+ return true; // No filtering support, nothing to do.
+ }
+ CANARD_ASSERT((self->vtable->filter != NULL) && mem_valid(self->mem.rx_filters));
+
+ // Allocate the temporary filter storage. Depending on the CAN hardware, it may be fairly large.
+ // Ideally we should cap it by the actual number of filters needed but we don't store that currently.
+ const size_t capacity = self->rx.filter_count;
+ canard_filter_t* const filters = mem_alloc_zero(self->mem.rx_filters, capacity * sizeof(canard_filter_t));
+ if (filters == NULL) {
+ self->err.oom++;
+ return false;
+ }
+
+ // Build the filter array. Use optimal coalescence if we have more subscriptions than filters available.
+ size_t n = 0;
+ for (size_t kind = 0; kind < CANARD_KIND_COUNT; kind++) {
+ for (const canard_subscription_t* sub = (canard_subscription_t*)(void*)cavl2_min(self->rx.subscriptions[kind]);
+ sub != NULL;
+ sub = (canard_subscription_t*)(void*)cavl2_next_greater((canard_tree_t*)sub)) {
+ const canard_filter_t f = rx_filter_for_subscription(self, sub->kind, sub->port_id);
+ if (n < capacity) {
+ filters[n++] = f;
+ } else {
+ rx_filter_coalesce_into(n, filters, f);
+ }
+ }
+ }
+ CANARD_ASSERT(n <= capacity);
+
+ // Force-admit Heartbeat/NodeStatus for node-ID occupancy tracking.
+ // This may be made optional at some point if the arrival load becomes a problem for small nodes.
+ static const struct
{
- CanardPortID port_id_mutable = port_id;
-
- struct CanardTreeNode* const sub_node =
- cavl2_find(ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID);
- if (sub_node != NULL)
- {
- struct CanardRxSubscription* const sub = CAVL2_TO_OWNER(sub_node, struct CanardRxSubscription, base);
- CANARD_ASSERT(sub->port_id == port_id);
- if (out_subscription != NULL)
- {
- *out_subscription = sub;
+ canard_kind_t kind;
+ uint16_t port_id;
+ } forced[] = {
+ { canard_kind_message_13b, 7509U }, // Cyphal v1.0 Heartbeat
+ { canard_kind_v0_message, 341U }, // DroneCAN NodeStatus
+ };
+ for (size_t i = 0; i < sizeof(forced) / sizeof(forced[0]); i++) {
+ const canard_filter_t f = rx_filter_for_subscription(self, forced[i].kind, forced[i].port_id);
+ if (!rx_filter_match(n, filters, f.extended_can_id)) {
+ if (n < capacity) {
+ filters[n++] = f;
+ } else {
+ rx_filter_coalesce_into(n, filters, f);
}
- out = 1;
}
- else
- {
- out = 0;
+ }
+ CANARD_ASSERT(n <= capacity);
+
+ // Apply the filters.
+ const bool ok = self->vtable->filter(self, n, filters);
+ mem_free(self->mem.rx_filters, capacity * sizeof(canard_filter_t), filters);
+ return ok;
+}
+
+// Common subscribe logic: validate, initialize, insert into tree, mark filters dirty.
+static bool rx_subscribe(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const canard_kind_t kind,
+ const uint16_t port_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable)
+{
+ bool ok = (self != NULL) && (subscription != NULL) && (vtable != NULL) && (vtable->on_message != NULL) &&
+ (transfer_id_timeout >= 0);
+ if (ok) {
+ (void)memset(subscription, 0, sizeof(*subscription));
+ subscription->transfer_id_timeout = transfer_id_timeout;
+ subscription->extent = extent;
+ subscription->port_id = port_id;
+ subscription->crc_seed = crc_seed;
+ subscription->kind = kind;
+ subscription->owner = self;
+ subscription->vtable = vtable;
+ const canard_tree_t* const existing = cavl2_find_or_insert(&self->rx.subscriptions[kind],
+ &subscription->port_id,
+ rx_subscription_cavl_compare,
+ &subscription->index_port_id,
+ cavl2_trivial_factory);
+ if (existing != &subscription->index_port_id) {
+ (void)memset(subscription, 0, sizeof(*subscription)); // Undo partial init on duplicate.
+ ok = false;
+ } else {
+ self->rx.filters_dirty = true;
}
}
- return out;
+ return ok;
}
-struct CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id)
+bool canard_subscribe_16b(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t subject_id,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable)
{
- struct CanardFilter out = {0};
+ return rx_subscribe(
+ self, subscription, canard_kind_message_16b, subject_id, CRC_INITIAL, extent, transfer_id_timeout, vtable);
+}
- out.extended_can_id = ((uint32_t) subject_id) << OFFSET_SUBJECT_ID;
- out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_07 | (CANARD_SUBJECT_ID_MAX << OFFSET_SUBJECT_ID);
+bool canard_subscribe_13b(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t subject_id,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable)
+{
+ return (subject_id <= CANARD_SUBJECT_ID_MAX_13b) &&
+ rx_subscribe(
+ self, subscription, canard_kind_message_13b, subject_id, CRC_INITIAL, extent, transfer_id_timeout, vtable);
+}
- return out;
+bool canard_subscribe_request(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t service_id,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable)
+{
+ return (service_id <= CANARD_SERVICE_ID_MAX) &&
+ rx_subscribe(
+ self, subscription, canard_kind_request, service_id, CRC_INITIAL, extent, transfer_id_timeout, vtable);
}
-struct CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id)
+bool canard_subscribe_response(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t service_id,
+ const size_t extent,
+ const canard_subscription_vtable_t* const vtable)
{
- struct CanardFilter out = {0};
+ return (service_id <= CANARD_SERVICE_ID_MAX) &&
+ rx_subscribe(self, subscription, canard_kind_response, service_id, CRC_INITIAL, extent, 0, vtable);
+}
- out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) service_id) << OFFSET_SERVICE_ID) |
- (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID);
- out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_SERVICE_ID_MAX << OFFSET_SERVICE_ID) |
- (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID);
+bool canard_v0_subscribe(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t data_type_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable)
+{
+ return rx_subscribe(self,
+ subscription,
+ canard_kind_v0_message,
+ data_type_id,
+ crc_seed,
+ extent + CRC_BYTES,
+ transfer_id_timeout,
+ vtable);
+}
- return out;
+bool canard_v0_subscribe_request(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable)
+{
+ return rx_subscribe(self,
+ subscription,
+ canard_kind_v0_request,
+ (uint16_t)data_type_id,
+ crc_seed,
+ extent + CRC_BYTES,
+ transfer_id_timeout,
+ vtable);
}
-struct CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id)
+bool canard_v0_subscribe_response(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_subscription_vtable_t* const vtable)
{
- struct CanardFilter out = {0};
+ return rx_subscribe(self, //
+ subscription,
+ canard_kind_v0_response,
+ (uint16_t)data_type_id,
+ crc_seed,
+ extent + CRC_BYTES,
+ 0,
+ vtable);
+}
- out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID);
- out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID);
+void canard_unsubscribe(canard_t* const self, canard_subscription_t* const subscription)
+{
+ CANARD_ASSERT((self != NULL) && (subscription != NULL) && (subscription->owner == self));
+ while (subscription->sessions != NULL) {
+ rx_session_destroy((rx_session_t*)(void*)cavl2_min(subscription->sessions));
+ }
+ cavl2_remove(&self->rx.subscriptions[subscription->kind], &subscription->index_port_id);
+ self->rx.filters_dirty = true;
+}
- return out;
+// --------------------------------------------- MISC ---------------------------------------------
+
+static void node_id_occupancy_reset(canard_t* const self)
+{
+ self->node_id_occupancy_bitmap[0] = 1; // Reserve 0 for compatibility with v0
+ self->node_id_occupancy_bitmap[1] = 0;
}
-struct CanardFilter canardConsolidateFilters(const struct CanardFilter* a, const struct CanardFilter* b)
+// Records the seen node-ID and reallocates the local node if a collision is found.
+static void node_id_occupancy_update(canard_t* const self, const byte_t src)
{
- struct CanardFilter out = {0};
+ if ((src == CANARD_NODE_ID_ANONYMOUS) ||
+ (bitmap_test(self->node_id_occupancy_bitmap, src) && (self->node_id != src))) {
+ return;
+ }
+ CANARD_ASSERT(src <= CANARD_NODE_ID_MAX);
+
+ // Update the node-ID occupancy bitmap. We cannot detect departures of an individual node, so in the presence of
+ // churn the slots will be eventually exhausted. We mitigate this by applying probabilistic purge once the
+ // population count exceeds some threshold, such that the purge probability is 1 when the bitmap is almost full.
+ // Such non-deterministic purge is preferable because it avoids spurious synchronization effects.
+ bitmap_set(self->node_id_occupancy_bitmap, src);
+ const byte_t cap = CANARD_NODE_ID_CAPACITY;
+ const byte_t pc = popcount(self->node_id_occupancy_bitmap[0]) + popcount(self->node_id_occupancy_bitmap[1]);
+ const byte_t zc = cap - pc; // zero count, the number of free slots
+ const bool purge = (pc > (cap / 2)) && chance(self, zc); // purge when dense but before full
+ CANARD_ASSERT(zc > 0); // at least one free slot is guaranteed because we add at most one bit per update
+
+ // Check for collision, reroll if needed. This must be done before we purge the occupancy map.
+ if (self->node_id == src) {
+ // Uniformly pick a cleared bit from the bitmap. It will become our new node-ID.
+ size_t id = 0;
+ size_t z = (size_t)random(self, zc);
+ CANARD_ASSERT(z < zc);
+ while (z > 0) {
+ if (!bitmap_test(self->node_id_occupancy_bitmap, id++)) {
+ z--;
+ }
+ CANARD_ASSERT(id < CANARD_NODE_ID_CAPACITY);
+ }
+ while (bitmap_test(self->node_id_occupancy_bitmap, id)) {
+ id++;
+ CANARD_ASSERT(id < CANARD_NODE_ID_CAPACITY);
+ }
- out.extended_mask = a->extended_mask & b->extended_mask & ~(a->extended_can_id ^ b->extended_can_id);
- out.extended_can_id = a->extended_can_id & out.extended_mask;
+ // Assign the new ID.
+ CANARD_ASSERT((0 < id) && (id < CANARD_NODE_ID_CAPACITY));
+ self->node_id = (byte_t)id;
+ CANARD_ASSERT(!bitmap_test(self->node_id_occupancy_bitmap, self->node_id));
- return out;
+ // Update dependent states.
+ tx_purge_continuations(self);
+ self->rx.filters_dirty = true;
+ self->err.collision++;
+ }
+
+ // The purge is delayed because we need the original occupancy map for reallocation.
+ if (purge) {
+ node_id_occupancy_reset(self);
+ bitmap_set(self->node_id_occupancy_bitmap, src);
+ }
+}
+
+bool canard_new(canard_t* const self,
+ const canard_vtable_t* const vtable,
+ const canard_mem_set_t memory,
+ const size_t tx_queue_capacity,
+ const uint64_t prng_seed,
+ const size_t filter_count)
+{
+ const bool filter_ok = (filter_count == 0) || //
+ ((vtable != NULL) && (vtable->filter != NULL) && mem_valid(memory.rx_filters));
+ const bool ok = (self != NULL) && (vtable != NULL) && (vtable->now != NULL) && (vtable->tx != NULL) &&
+ mem_valid(memory.tx_transfer) && mem_valid(memory.tx_frame) && mem_valid(memory.rx_session) &&
+ mem_valid(memory.rx_payload) && filter_ok;
+ if (ok) {
+ (void)memset(self, 0, sizeof(*self));
+ self->tx.fd = true;
+ self->tx.queue_capacity = tx_queue_capacity;
+ self->rx.filter_count = filter_count;
+ self->mem = memory;
+ self->prng_state = prng_seed ^ (uintptr_t)self;
+ self->vtable = vtable;
+ self->node_id = (byte_t)(random(self, CANARD_NODE_ID_MAX) + 1U); // [1, 127]
+ node_id_occupancy_reset(self);
+ }
+ return ok;
+}
+
+void canard_destroy(canard_t* const self)
+{
+ CANARD_ASSERT(self != NULL);
+ // The application MUST destroy all subscriptions before destroying the instance.
+ for (size_t i = 0; i < (sizeof(self->rx.subscriptions) / sizeof(self->rx.subscriptions[0])); i++) {
+ CANARD_ASSERT(self->rx.subscriptions[i] == NULL);
+ }
+ CANARD_ASSERT(self->rx.list_session_by_animation.head == NULL);
+ CANARD_ASSERT(self->rx.list_session_by_animation.tail == NULL);
+ while (self->tx.agewise.head != NULL) {
+ tx_transfer_t* const tr = LIST_HEAD(self->tx.agewise, tx_transfer_t, list_agewise);
+ tx_retire(self, tr);
+ }
+ (void)memset(self, 0, sizeof(*self)); // UAF safety
+}
+
+bool canard_set_node_id(canard_t* const self, const uint_least8_t node_id)
+{
+ const bool ok = (self != NULL) && (node_id <= CANARD_NODE_ID_MAX);
+ if (ok && (node_id != self->node_id)) {
+ self->node_id = node_id;
+ // If the source node-ID changes, started multi-frame continuations become invalid and must be canceled.
+ tx_purge_continuations(self);
+ node_id_occupancy_reset(self);
+ self->rx.filters_dirty = true;
+ }
+ return ok;
+}
+
+void canard_poll(canard_t* const self, const uint_least8_t tx_ready_iface_bitmap)
+{
+ if (self != NULL) {
+ self->rx.filters_dirty = self->rx.filters_dirty && !rx_filter_configure(self);
+
+ // Drop stale sessions to reclaim memory. This happens when remote peers cease sending data.
+ // The oldest is held alive until its session timeout has expired, but notice that it may be different
+ // depending on the subscription instance if large transfer-ID values are used.
+ // This means that a stale session that belongs to a subscription with a long timeout may keep other sessions
+ // with a shorter timeout alive beyond their expiration time.
+ // We accept this because it does not affect correctness (the transfer-ID timeout is checked on reception
+ // always); the only downside is that memory reclamation time is bounded in the worst case by the longest
+ // transfer-ID timeout among all subscriptions, but this is a reasonable tradeoff for the reduced complexity.
+ rx_session_t* const ses = LIST_HEAD(self->rx.list_session_by_animation, rx_session_t, list_animation);
+ const canard_us_t now = self->vtable->now(self);
+ if (ses != NULL) {
+ const size_t in_progress_slots = rx_session_cleanup(ses, now);
+ if ((in_progress_slots == 0) && (ses->last_admission_ts < (now - ses->owner->transfer_id_timeout))) {
+ rx_session_destroy(ses);
+ }
+ }
+
+ // Process the TX pipeline.
+ tx_expire(self, now); // deadline maintenance first to keep queue pressure bounded
+ FOREACH_IFACE (i) { // submit queued frames through all currently writable interfaces
+ if ((tx_ready_iface_bitmap & (1U << i)) != 0U) {
+ tx_eject_pending(self, (byte_t)i);
+ }
+ }
+ }
+}
+
+static void ingest_frame(canard_t* const self,
+ const canard_us_t timestamp,
+ const uint_least8_t iface_index,
+ const frame_t frame)
+{
+ // Update the node-ID occupancy/collision before routing. Only on start frames to manage load.
+ if (frame.start) {
+ node_id_occupancy_update(self, frame.src);
+ }
+ // Route the frame to the appropriate destination internally.
+ canard_subscription_t* const sub = rx_route(self, &frame);
+ if (sub != NULL) {
+ rx_session_update(sub, timestamp, &frame, iface_index);
+ }
+}
+
+bool canard_ingest_frame(canard_t* const self,
+ const canard_us_t timestamp,
+ const uint_least8_t iface_index,
+ const uint32_t extended_can_id,
+ const canard_bytes_t can_data)
+{
+ const bool ok = (self != NULL) && (timestamp >= 0) && (iface_index < CANARD_IFACE_COUNT) &&
+ (extended_can_id <= CAN_EXT_ID_MASK) && ((can_data.size == 0) || (can_data.data != NULL));
+ if (ok) {
+ frame_t frs[2] = { { 0 }, { 0 } };
+ const byte_t parsed = rx_parse(extended_can_id, can_data, &frs[0], &frs[1]);
+ if (parsed == 0) {
+ self->err.rx_frame++;
+ }
+ if ((parsed & 1U) != 0) {
+ CANARD_ASSERT(canard_kind_version(frs[0].kind) == 0);
+ ingest_frame(self, timestamp, iface_index, frs[0]);
+ }
+ if ((parsed & 2U) != 0) {
+ CANARD_ASSERT(canard_kind_version(frs[1].kind) == 1);
+ ingest_frame(self, timestamp, iface_index, frs[1]);
+ }
+ }
+ return ok;
+}
+
+uint16_t canard_v0_crc_seed_from_data_type_signature(const uint64_t data_type_signature)
+{
+ uint16_t crc = CRC_INITIAL;
+ uint64_t sig = data_type_signature;
+ for (size_t i = 0; i < 8U; i++) {
+ crc = crc_add_byte(crc, (byte_t)(sig & BYTE_MAX));
+ sig >>= 8U;
+ }
+ return crc;
}
diff --git a/libcanard/canard.h b/libcanard/canard.h
index bdc53ea2..a14b1695 100644
--- a/libcanard/canard.h
+++ b/libcanard/canard.h
@@ -5,80 +5,28 @@
/// `____/ .___/`___/_/ /_/`____/`__, / .___/_/ /_/`__,_/_/
/// /_/ /____/_/
///
-/// Libcanard is a compact implementation of the Cyphal/CAN protocol for high-integrity real-time embedded systems.
-/// It is designed for use in robust deterministic embedded systems equipped with at least 32K ROM and 8K RAM.
-/// The codebase follows the MISRA C rules, has 100% test coverage, and is validated by at least two static analyzers.
+/// Libcanard is a compact implementation of the Cyphal/CAN transport for high-integrity real-time embedded systems.
+/// It is designed for use in robust deterministic embedded systems equipped with at least 32K ROM and RAM.
/// The library is designed to be compatible with any target platform and instruction set architecture, from 8 to 64
-/// bit, little- and big-endian, RTOS-based or baremetal, etc., as long as there is a standards-compliant compiler.
+/// bit, little- and big-endian, RTOS-based or baremetal, etc., as long as there is a standards-compliant C compiler.
///
-/// INTEGRATION
+/// The library offers a non-blocking callback-based API. It is not thread-safe: if used in a concurrent environment,
+/// it is the responsibility of the application to provide adequate synchronization.
+///
+/// The library supports both Cyphal v1 and the legacy UAVCAN v0 (aka DroneCAN) protocol versions,
+/// which can be used simultaneously on the same bus, with one limitation that a single node cannot send transfers
+/// of both versions simultaneously (unless certain constraints are satisfied as discussed below). If an application
+/// needs to send transfers of both versions simultaneously, the recommended solution is to run two node instances.
///
/// The library is intended to be integrated into the end application by simply copying its source files into the
/// source tree of the project; it does not require any special compilation options and should work out of the box.
/// There are build-time configuration parameters defined near the top of canard.c, but they are safe to ignore.
///
-/// As explained in this documentation, the library requires a deterministic constant-time bounded-fragmentation dynamic
-/// memory allocator. If your target platform does not provide a deterministic memory manager (most platforms don't),
-/// it is recommended to use O1Heap (MIT licensed): https://github.com/pavel-kirienko/o1heap.
-///
-/// There are no specific requirements to the underlying I/O layer. Some low-level drivers maintained by the
-/// OpenCyphal team may be found at https://github.com/OpenCyphal-Garage/platform_specific_components.
-///
-/// If your application requires a MISRA C compliance report, please get in touch with the maintainers via the forum
-/// at https://forum.opencyphal.org.
-///
-/// ARCHITECTURE
-///
-/// Cyphal, as a protocol stack, is composed of two layers: TRANSPORT and PRESENTATION. The transport layer is portable
-/// across different transport protocols, one of which is CAN (FD), formally referred to as Cyphal/CAN. This library
-/// is focused on Cyphal/CAN only and it will not support other transports. The presentation layer is implemented
-/// through the DSDL language and the associated data type regulation policies; these parts are out of the scope of
-/// this library as it is focused purely on the transport.
-///
-/// This library consists of two components: the transmission (TX) pipeline and the reception (RX) pipeline.
-/// The pipelines are completely independent from each other except that they both rely on the same dynamic memory
-/// manager. The TX pipeline uses the dynamic memory to store outgoing CAN frames in the prioritized transmission
-/// queue. The RX pipeline uses the dynamic memory to store contiguous payload buffers for received transfers and
-/// for keeping the transfer reassembly state machine data. The exact memory consumption model is defined for both
-/// pipelines, so it is possible to statically determine the minimum size of the dynamic memory pool required to
-/// guarantee that a given application will never encounter an out-of-memory error at runtime.
-///
-/// Much like with dynamic memory, the time complexity of every API function is well-characterized, allowing the
-/// application to guarantee predictable real-time performance.
-///
-/// The TX pipeline is managed with the help of five API functions. The first one -- canardTxInit() -- is used for
-/// constructing a new TX queue, of which there should be as many as there are redundant CAN interfaces;
-/// each queue is managed independently. When the application needs to emit a transfer, it invokes canardTxPush()
-/// on each queue separately. The function splits the transfer into CAN frames and stores them into the queue.
-/// The application then picks the produced CAN frames from the queue one-by-one by calling canardTxPeek() followed
-/// by canardTxPop() -- the former allows the application to look at the next frame scheduled for transmission,
-/// and the latter tells the library that the frame shall be removed from the queue.
-/// Popped frames need to be manually deallocated by the application upon transmission by calling canardTxFree().
-///
-/// The RX pipeline is managed with the help of three API functions; unlike the TX pipeline, there is one shared
-/// state for all redundant interfaces that manages deduplication transparently. The main function canardRxAccept()
-/// takes a received CAN frame and updates the appropriate transfer reassembly state machine. The functions
-/// canardRxSubscribe() and its counterpart canardRxUnsubscribe() instruct the library which transfers should be
-/// received (by default, all transfers are ignored); also, the subscription function specifies vital transfer
-/// reassembly parameters such as the maximum payload size (i.e., the maximum size of a serialized representation
-/// of a DSDL object) and the transfer-ID timeout. Transfers that carry more payload than the configured maximum per
-/// subscription are truncated following the Implicit Truncation Rule (ITR) defined by the Cyphal Specification --
-/// the rule is implemented to facilitate backward-compatible DSDL data type extensibility.
-///
-/// The library supports a practically unlimited number of redundant interfaces.
-///
-/// The library is not thread-safe: if used in a concurrent environment, it is the responsibility of the application
-/// to provide adequate synchronization.
-///
-/// The library is purely reactive: it does not perform any background processing and does not require periodic
-/// servicing. Its internal state is only updated as a response to well-specified external events.
-///
/// --------------------------------------------------------------------------------------------------------------------
-///
/// This software is distributed under the terms of the MIT License.
/// Copyright (c) OpenCyphal.
/// Author: Pavel Kirienko
-/// Contributors: https://github.com/OpenCyphal/libcanard/contributors.
+/// Contributors: https://github.com/OpenCyphal/libcanard/contributors
#ifndef CANARD_H_INCLUDED
#define CANARD_H_INCLUDED
@@ -88,765 +36,600 @@
#include
#ifdef __cplusplus
-extern "C" {
+extern "C"
+{
#endif
-/// Semantic version of this library (not the Cyphal specification).
-/// API will be backward compatible within the same major version.
-#define CANARD_VERSION_MAJOR 4
+#define CANARD_VERSION_MAJOR 5
#define CANARD_VERSION_MINOR 0
-/// The version number of the Cyphal specification implemented by this library.
-#define CANARD_CYPHAL_SPECIFICATION_VERSION_MAJOR 1
-#define CANARD_CYPHAL_SPECIFICATION_VERSION_MINOR 0
+#define CANARD_CYPHAL_VERSION_MAJOR 1
+#define CANARD_CYPHAL_VERSION_MINOR 1
-/// These error codes may be returned from the library API calls whose return type is a signed integer in the negated
-/// form (e.g., error code 2 returned as -2). A non-negative return value represents success.
-/// API calls whose return type is not a signed integer cannot fail by contract.
-/// No other error states may occur in the library.
-/// By contract, a well-characterized application with a properly sized memory pool will never encounter errors.
-/// The error code 1 is not used because -1 is often used as a generic error code in 3rd-party code.
-#define CANARD_ERROR_INVALID_ARGUMENT 2
-#define CANARD_ERROR_OUT_OF_MEMORY 3
+/// The library will support at most this many local redundant network interfaces.
+/// This parameter affects the size of several heap-allocated structures.
+/// It is safe to pick any large value but the heap memory footprint will increase accordingly.
+#ifndef CANARD_IFACE_COUNT
+#define CANARD_IFACE_COUNT 2U
+#endif
+#if (CANARD_IFACE_COUNT < 1) || (CANARD_IFACE_COUNT > 8)
+#error "CANARD_IFACE_COUNT must be in the range [1, 8]"
+#endif
+#define CANARD_IFACE_BITMAP_ALL ((1U << CANARD_IFACE_COUNT) - 1U)
+
+/// Parameter ranges are inclusive; the lower bound is zero for all.
+#define CANARD_SUBJECT_ID_MAX 0xFFFFU // Applies to Cyphal v1.1 and UAVCAN v0/DroneCAN message data type IDs.
+#define CANARD_SUBJECT_ID_MAX_13b 8191U // Cyphal v1.0 supports only 13-bit subject-IDs.
+#define CANARD_SERVICE_ID_MAX 511U // Applies to Cyphal, all versions. In v0 this is narrower.
+#define CANARD_NODE_ID_MAX 127U
+#define CANARD_NODE_ID_CAPACITY (CANARD_NODE_ID_MAX + 1U)
+#define CANARD_TRANSFER_ID_BITS 5U
+#define CANARD_TRANSFER_ID_MODULO (1U << CANARD_TRANSFER_ID_BITS)
+#define CANARD_TRANSFER_ID_MAX (CANARD_TRANSFER_ID_MODULO - 1U)
+
+/// This is used only with Cyphal v1.0 and legacy v0 protocols to indicate anonymous messages.
+/// This library can receive anonymous messages but it cannot transmit them; it implements a new, simpler stateless
+/// node-ID autoconfiguration protocol instead that makes anonymous messages unnecessary.
+#define CANARD_NODE_ID_ANONYMOUS 0xFFU
+
+/// This is the recommended transfer-ID timeout value given in the Cyphal Specification. The application may choose
+/// different values per subscription (i.e., per data specifier) depending on its timing requirements.
+/// Within this timeout, the library will refuse to accept a transfer with the same transfer-ID as the last one
+/// received on the same subject from the same source node.
+#define CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_us 2000000UL
/// MTU values for the supported protocols.
/// Per the recommendations given in the Cyphal/CAN Specification, other MTU values should not be used.
#define CANARD_MTU_CAN_CLASSIC 8U
-#define CANARD_MTU_CAN_FD 64U
-#define CANARD_MTU_MAX CANARD_MTU_CAN_FD
+#define CANARD_MTU_CAN_FD 64U
-/// Parameter ranges are inclusive; the lower bound is zero for all. See Cyphal/CAN Specification for background.
-#define CANARD_SUBJECT_ID_MAX 8191U
-#define CANARD_SERVICE_ID_MAX 511U
-#define CANARD_NODE_ID_MAX 127U
-#define CANARD_PRIORITY_MAX 7U
-#define CANARD_TRANSFER_ID_BIT_LENGTH 5U
-#define CANARD_TRANSFER_ID_MAX ((1U << CANARD_TRANSFER_ID_BIT_LENGTH) - 1U)
+/// All valid transfer kind and version combinations.
+///
+/// Distinct message types use separate ID spaces; i.e., any given ID may be used with distinct message kinds without
+/// collision/ambiguity. For example, in the original Cyphal v1.0, subject-ID 7509 is assigned to the heartbeat message,
+/// while in v1.1 there are no fixed subject-IDs at all and 7509 has no special meaning. Likewise, the data type ID
+/// of the legacy UAVCAN v0 is a separate ID space.
+///
+/// Request and response under the same protocol version share the same ID space.
+typedef enum canard_kind_t
+{
+ canard_kind_message_16b = 0, ///< 16-bit subject-ID message introduced in Cyphal v1.1. Isolated subject-ID space.
+ canard_kind_message_13b = 1, ///< 13-bit subject-ID message originally defined in Cyphal v1.0.
+ canard_kind_response = 2, ///< Cyphal v1 RPC-service response.
+ canard_kind_request = 3, ///< Cyphal v1 RPC-service request.
+ // Legacy DroneCAN/UAVCAN v0 transfer kinds.
+ canard_kind_v0_message = 4,
+ canard_kind_v0_response = 5,
+ canard_kind_v0_request = 6,
+} canard_kind_t;
+#define CANARD_KIND_COUNT 7
+
+static inline uint_least8_t canard_kind_version(const canard_kind_t kind)
+{
+ return (kind < canard_kind_v0_message) ? 1 : 0;
+}
-/// This value represents an undefined node-ID: broadcast destination or anonymous source.
-/// Library functions treat all values above CANARD_NODE_ID_MAX as anonymous.
-#define CANARD_NODE_ID_UNSET 255U
+typedef struct canard_t canard_t;
-/// This is the recommended transfer-ID timeout value given in the Cyphal Specification. The application may choose
-/// different values per subscription (i.e., per data specifier) depending on its timing requirements.
-#define CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC 2000000UL
+/// Monotonic time in microseconds; the current time is never negative.
+typedef int64_t canard_us_t;
-// Forward declarations.
-typedef uint64_t CanardMicrosecond;
-typedef uint16_t CanardPortID;
-typedef uint8_t CanardNodeID;
-typedef uint8_t CanardTransferID;
+/// Length to DLC rounds up.
+extern const uint_least8_t canard_dlc_to_len[16];
+extern const uint_least8_t canard_len_to_dlc[65];
-/// Transfer priority level mnemonics per the recommendations given in the Cyphal Specification.
-enum CanardPriority
+typedef enum canard_prio_t
{
- CanardPriorityExceptional = 0,
- CanardPriorityImmediate = 1,
- CanardPriorityFast = 2,
- CanardPriorityHigh = 3,
- CanardPriorityNominal = 4, ///< Nominal priority level should be the default.
- CanardPriorityLow = 5,
- CanardPrioritySlow = 6,
- CanardPriorityOptional = 7,
-};
-
-/// Transfer kinds as defined by the Cyphal Specification.
-enum CanardTransferKind
+ canard_prio_exceptional = 0,
+ canard_prio_immediate = 1,
+ canard_prio_fast = 2,
+ canard_prio_high = 3,
+ canard_prio_nominal = 4, ///< Nominal priority level should be the default.
+ canard_prio_low = 5,
+ canard_prio_slow = 6,
+ canard_prio_optional = 7,
+} canard_prio_t;
+#define CANARD_PRIO_COUNT 8U
+#define CANARD_PRIO_BITS 3U
+
+typedef struct canard_tree_t
{
- CanardTransferKindMessage = 0, ///< Multicast, from publisher to all subscribers.
- CanardTransferKindResponse = 1, ///< Point-to-point, from server to client.
- CanardTransferKindRequest = 2, ///< Point-to-point, from client to server.
+ struct canard_tree_t* up;
+ struct canard_tree_t* lr[2];
+ int_fast8_t bf;
+} canard_tree_t;
+
+typedef struct canard_listed_t canard_listed_t;
+typedef struct canard_list_t canard_list_t;
+struct canard_listed_t
+{
+ canard_listed_t* next;
+ canard_listed_t* prev;
};
-#define CANARD_NUM_TRANSFER_KINDS 3
-
-/// The AVL tree node structure is exposed here to avoid pointer casting/arithmetics inside the library.
-/// The user code is not expected to interact with this type except if advanced introspection is required.
-struct CanardTreeNode
+struct canard_list_t
{
- struct CanardTreeNode* up; ///< Do not access this field.
- struct CanardTreeNode* lr[2]; ///< Left and right children of this node may be accessed for tree traversal.
- int8_t bf; ///< Do not access this field.
+ canard_listed_t* head; ///< NULL if list empty
+ canard_listed_t* tail; ///< NULL if list empty
};
-struct CanardPayload
+typedef struct canard_bytes_t canard_bytes_t;
+typedef struct canard_bytes_chain_t canard_bytes_chain_t;
+typedef struct canard_bytes_mut_t canard_bytes_mut_t;
+struct canard_bytes_t
{
- /// If size=0, the data pointer may be NULL.
size_t size;
const void* data;
};
-
-struct CanardMutablePayload
+struct canard_bytes_chain_t
+{
+ canard_bytes_t bytes;
+ const canard_bytes_chain_t* next; ///< NULL in the last fragment.
+};
+struct canard_bytes_mut_t
{
- /// If size=0, the data pointer may be NULL.
size_t size;
void* data;
-
- /// Always allocated_size >= size. Can be zero if the data pointer is NULL.
- /// When deallocating memory, the allocated_size should be used as the argument to the allocator, not size.
- size_t allocated_size;
};
-/// CAN data frame with an extended 29-bit ID. RTR/Error frames are not used and therefore not modeled here.
-/// CAN frames with 11-bit ID are not used by Cyphal/CAN and so they are not supported by the library.
-struct CanardFrame
+/// canard_mem_t models a memory resource for allocating a particular kind of objects used by the library.
+/// The semantics are similar to malloc/free. It is designed to be passed by value.
+/// Consider using O1Heap: https://github.com/pavel-kirienko/o1heap.
+/// The API documentation is written on the assumption that the memory management functions are O(1).
+typedef struct canard_mem_t canard_mem_t;
+typedef struct canard_mem_vtable_t canard_mem_vtable_t;
+struct canard_mem_vtable_t
{
- /// 29-bit extended ID. The bits above 29-th shall be zero.
- uint32_t extended_can_id;
-
- /// The useful data in the frame. The length value is not to be confused with DLC!
- /// If the payload is empty (payload.size = 0), the payload.data pointer may be NULL.
- /// For RX frames: the library does not expect the lifetime of the pointee to extend beyond the point of return
- /// from the API function. That is, the pointee can be invalidated immediately after the frame has been processed.
- /// For TX frames: the frame and the payload are allocated within the same dynamic memory fragment, so their
- /// lifetimes are identical; when the frame is freed, the payload is invalidated.
- /// A more detailed overview of the dataflow and related resource management issues is provided in the API docs.
- struct CanardPayload payload;
+ void (*free)(canard_mem_t, size_t, void*);
+ void* (*alloc)(canard_mem_t, size_t);
};
-
-/// Similar to the CanardFrame structure, but with a mutable payload (including allocated_size of the payload).
-/// In use when payload memory ownership might be transferred.
-struct CanardMutableFrame
+struct canard_mem_t
{
- uint32_t extended_can_id;
- struct CanardMutablePayload payload;
+ const canard_mem_vtable_t* vtable;
+ void* context;
};
-/// Conversion look-up table from CAN DLC to data length.
-extern const uint8_t CanardCANDLCToLength[16];
-
-/// Conversion look-up table from data length to CAN DLC; the length is rounded up.
-extern const uint8_t CanardCANLengthToDLC[65];
-
-/// A Cyphal transfer metadata (everything except the payload).
-/// Per Specification, a transfer is represented on the wire as a non-empty set of transport frames (i.e., CAN frames).
-/// The library is responsible for serializing transfers into transport frames when transmitting, and reassembling
-/// transfers from an incoming stream of frames (possibly duplicated if redundant interfaces are used) during reception.
-struct CanardTransferMetadata
+/// Represents received transfer payload.
+/// The application shall access the useful payload through view and use origin only for lifetime management.
+/// For multi-frame transfers, the view points into dynamically allocated rx_payload storage and origin owns it;
+/// release non-empty origin with the same resource used for canard_mem_set_t::rx_payload.
+/// For single-frame transfers, the view is pointing into the CAN frame data buffer passed by the application via
+/// canard_ingest_frame(), and the storage is NULL/empty. The lifetime of the view ends upon return from the callback.
+/// The application must manually copy the data if it needs to outlive the callback.
+typedef struct canard_payload_t
{
- /// Per the Specification, all frames belonging to a given transfer shall share the same priority level.
- /// If this is not the case, then this field contains the priority level of the last frame to arrive.
- enum CanardPriority priority;
-
- enum CanardTransferKind transfer_kind;
-
- /// Subject-ID for message publications; service-ID for service requests/responses.
- CanardPortID port_id;
-
- /// For outgoing message transfers the value shall be CANARD_NODE_ID_UNSET (otherwise the state is invalid).
- /// For outgoing service transfers this is the destination address (invalid if unset).
- /// For incoming non-anonymous transfers this is the node-ID of the origin.
- /// For incoming anonymous transfers the value is reported as CANARD_NODE_ID_UNSET.
- CanardNodeID remote_node_id;
-
- /// When responding to a service request, the response transfer SHALL have the same transfer-ID value as the
- /// request because the client will match the response with the request based on that.
- ///
- /// When publishing a message transfer, the value SHALL be one greater than the previous transfer under the same
- /// subject-ID; the initial value should be zero.
- ///
- /// When publishing a service request transfer, the value SHALL be one greater than the previous transfer under
- /// the same service-ID addressed to the same server node-ID; the initial value should be zero.
- ///
- /// Upon overflow, the value SHALL be reset back to zero.
- /// Values above CANARD_TRANSFER_ID_MAX are permitted -- the library will compute the modulo automatically.
- /// For received transfers, the values never exceed CANARD_TRANSFER_ID_MAX.
- ///
- /// A simple and robust way of managing transfer-ID counters is to keep a separate static variable per subject-ID
- /// and per (service-ID, server-node-ID) pair.
- CanardTransferID transfer_id;
-};
+ canard_bytes_t view; ///< Use this to access the data.
+ canard_bytes_mut_t origin; ///< Use this to free the memory, unless NULL/empty.
+} canard_payload_t;
-/// A pointer to the memory allocation function. The semantics are similar to malloc():
-/// - The returned pointer shall point to an uninitialized block of memory that is at least size bytes large.
-/// - If there is not enough memory, the returned pointer shall be NULL.
-/// - The memory shall be aligned at least at max_align_t.
-/// - The execution time should be constant (O(1)).
-/// - The worst-case memory fragmentation should be bounded and easily predictable.
-/// If the standard dynamic memory manager of the target platform does not satisfy the above requirements,
-/// consider using O1Heap: https://github.com/pavel-kirienko/o1heap.
-///
-/// The value of the user reference is taken from the corresponding field of the memory resource structure.
-typedef void* (*CanardMemoryAllocate)(void* const user_reference, const size_t size);
-
-/// The counterpart of the above -- this function is invoked to return previously allocated memory to the allocator.
-/// The semantics are similar to free(), but with additional size parameter:
-/// - The pointer was previously returned by the allocation function.
-/// - The pointer may be NULL, in which case the function shall have no effect.
-/// - The execution time should be constant (O(1)).
-/// - The size is the same as it was during allocation.
-///
-/// The value of the user reference is taken from the corresponding field of the memory resource structure.
-typedef void (*CanardMemoryDeallocate)(void* const user_reference, const size_t size, void* const pointer);
-
-/// A kind of memory resource that can only be used to free memory previously allocated by the user.
-/// Instances are mostly intended to be passed by value.
-struct CanardMemoryDeleter
+/// The filter only matches extended CAN IDs on data frames (no std/rtr). Bits above 29 are always zero.
+typedef struct canard_filter_t
{
- void* user_reference; ///< Passed as the first argument.
- CanardMemoryDeallocate deallocate; ///< Shall be a valid pointer.
-};
+ uint32_t extended_can_id;
+ uint32_t extended_mask;
+} canard_filter_t;
-/// A memory resource encapsulates the dynamic memory allocation and deallocation facilities.
-/// Note that the library allocates a large amount of small fixed-size objects for bookkeeping purposes;
-/// allocators for them can be implemented using fixed-size block pools to eliminate extrinsic memory fragmentation.
-/// Instances are mostly intended to be passed by value.
-struct CanardMemoryResource
+/// Each resource is used for allocating memory for a specific purpose.
+/// This enables fine-tuning in memory-conscious applications.
+/// Ordinary applications can use the same resource for everything; alloc/free are assumed O(1) [e.g., use o1heap].
+typedef struct canard_mem_set_t
{
- void* user_reference; ///< Passed as the first argument.
- CanardMemoryDeallocate deallocate; ///< Shall be a valid pointer.
- CanardMemoryAllocate allocate; ///< Shall be a valid pointer.
-};
-
-/// The handler function is intended to be invoked from Canard TX polling (see details for the canardTxPoll()).
-/// The user reference parameter is what was passed to canardTxPoll.
-/// The return result of the handling operation:
-///
-/// - Any positive value: the frame was successfully handed over to the lower layer for transmission.
-/// The frame will be removed from the TX queue.
-///
-/// - Zero: the frame could not be handed over to the lower layer for transmission because it is not ready
-/// to accept one. Another attempt will be made at a later time when canardTxPoll() is invoked again.
-///
-/// - Any negative value: the frame was rejected due to an unrecoverable error.
-/// This frame along with all other frames of its transfer will be dropped from the TX queue.
-/// The statistical counters of this TX queue instance will be incremented accordingly.
-typedef int8_t (*CanardTxFrameHandler)(void* const user_reference,
- const CanardMicrosecond deadline_usec,
- struct CanardMutableFrame* const frame);
-
-/// Prioritized transmission queue that keeps CAN frames destined for transmission via one CAN interface.
-/// Applications with redundant interfaces are expected to have one instance of this type per interface.
-/// Applications that are not interested in transmission may have zero queues.
-/// All operations (push, peek, pop) are O(log n); there are exactly two heap allocations per element:
-/// 1. For bookkeeping purposes -- CanardTxQueueItem.
-/// 2. For payload storage -- the frame data itself transmitted over the wire.
-/// API functions that work with this type are named "canardTx*()", find them below.
-struct CanardTxQueue
+ canard_mem_t tx_transfer; ///< TX transfer objects, fixed-size, one per enqueued transfer.
+ canard_mem_t tx_frame; ///< One per enqueued frame, at least one per TX transfer, size MTU+overhead.
+ canard_mem_t rx_session; ///< Remote-associated sessions per subscriber, fixed-size.
+ canard_mem_t rx_payload; ///< Variable-size, max size extent+sizeof(rx_slot_t).
+ canard_mem_t rx_filters; ///< For canard_filter_t[filter_count] temporary storage. Not needed if filters not used.
+} canard_mem_set_t;
+
+typedef struct canard_subscription_t canard_subscription_t;
+typedef struct canard_subscription_vtable_t canard_subscription_vtable_t;
+struct canard_subscription_vtable_t
{
- /// The maximum number of frames this queue is allowed to contain. An attempt to push more will fail with an
- /// out-of-memory error even if the memory is not exhausted. This value can be changed by the user at any moment.
- /// The purpose of this limitation is to ensure that a blocked queue does not exhaust the heap memory.
- size_t capacity;
-
- /// The transport-layer maximum transmission unit (MTU). The value can be changed arbitrarily at any time between
- /// pushes. It defines the maximum number of data bytes per CAN data frame in outgoing transfers via this queue.
- ///
- /// Only the standard values should be used as recommended by the specification;
- /// otherwise, networking interoperability issues may arise. See recommended values CANARD_MTU_*.
- ///
- /// Valid values are any valid CAN frame data length value not smaller than 8.
- /// Invalid values are treated as the nearest valid value. The default is the maximum valid value.
- size_t mtu_bytes;
-
- /// The number of frames that are currently contained in the queue, initially zero.
- /// Do not modify this field!
- size_t size;
-
- /// The root of the priority queue is NULL if the queue is empty. Do not modify this field!
- struct CanardTreeNode* priority_root;
-
- /// The root of the deadline queue is NULL if the queue is empty. Do not modify this field!
- struct CanardTreeNode* deadline_root;
-
- /// The memory resource used by this queue for allocating the payload data (CAN frames).
- /// There is exactly one allocation of payload buffer per enqueued item (not considering the item itself
- /// b/c it is allocated from a different memory resource -- see CanardInstance::memory).
- /// The size of the allocation is equal to the MTU of the queue except for the last frame.
- /// The memory for the queue item is allocated separately from the instance memory resource.
- ///
- /// In a simple application, there would be just one memory resource shared by all parts of the library.
- /// If the application knows its MTU, it can use fixed-size block allocation to avoid extrinsic fragmentation,
- /// as well as a dedicated memory pool specifically for the TX queue payload for transmission.
- /// Dedicated memory resources could be useful also for systems with special memory requirements for payload data.
- /// For example, such a memory resource could be integrated with the CAN message RAM, so that memory
- /// is allocated directly in the peripheral's address space eliminating an extra copy.
- struct CanardMemoryResource memory;
-
- /// This field can be arbitrarily mutated by the user. It is never accessed by the library.
- /// Its purpose is to simplify integration with OOP interfaces.
- void* user_reference;
+ /// A new message is received on a subscription.
+ /// For the payload ownership notes refer to canard_payload_t.
+ /// The timestamp is the arrival timestamp of the first frame of the transfer.
+ void (*on_message)(canard_subscription_t* self,
+ canard_us_t timestamp,
+ canard_prio_t priority,
+ uint_least8_t source_node_id,
+ uint_least8_t transfer_id,
+ canard_payload_t payload);
};
-/// One frame stored in the transmission queue along with its metadata.
-struct CanardTxQueueItem
+/// Subscription instances must not be moved while in use.
+/// Each subscription is indexed by its port-ID inside the canard instance, and in turn contains a tree of sessions
+/// indexed by remote node-ID. Two log-time lookups are thus required to handle an incoming frame.
+/// None of the fields may be mutated by the application after initialization except for the user context.
+struct canard_subscription_t
{
- /// Internal use only; do not access this field.
- struct CanardTreeNode priority_base;
-
- /// Internal use only; do not access this field.
- struct CanardTreeNode deadline_base;
+ canard_tree_t index_port_id; ///< Must be the first member.
- /// Points to the next frame in this transfer or NULL. This field is mostly intended for own needs of the library.
- /// Normally, the application would not use it because transfer frame ordering is orthogonal to global TX ordering.
- /// It can be useful though for pulling pending frames from the TX queue if at least one frame of their transfer
- /// failed to transmit; the idea is that if at least one frame is missing, the transfer will not be received by
- /// remote nodes anyway, so all its remaining frames can be dropped from the queue at once using canardTxPop().
- struct CanardTxQueueItem* next_in_transfer;
+ canard_us_t transfer_id_timeout;
+ size_t extent; ///< Must not be altered after initialization! In v0 includes the CRC.
+ uint16_t port_id; ///< Represents subjects, services, and legacy message- and service data type IDs.
+ uint16_t crc_seed; ///< For v0 this is set at subscription time, for v1 this is always 0xFFFF.
+ canard_kind_t kind;
- /// This is the same value that is passed to canardTxPush().
- /// Frames whose transmission deadline is in the past shall be dropped.
- CanardMicrosecond tx_deadline_usec;
-
- /// The actual CAN frame data.
- struct CanardMutableFrame frame;
-};
+ canard_t* owner;
+ canard_tree_t* sessions;
+ const canard_subscription_vtable_t* vtable;
-/// Transfer subscription state. The application can register its interest in a particular kind of data exchanged
-/// over the bus by creating such subscription objects. Frames that carry data for which there is no active
-/// subscription will be silently dropped by the library. The entire RX pipeline is invariant to the number of
-/// redundant CAN interfaces used.
-///
-/// SUBSCRIPTION INSTANCES SHALL NOT BE MOVED WHILE IN USE.
-///
-/// The memory footprint of a subscription is large. On a 32-bit platform it slightly exceeds half a KiB.
-/// This is an intentional time-memory trade-off: use a large look-up table to ensure predictable temporal properties.
-struct CanardRxSubscription
-{
- struct CanardTreeNode base; ///< Read-only DO NOT MODIFY THIS
-
- CanardMicrosecond transfer_id_timeout_usec;
- size_t extent; ///< Read-only DO NOT MODIFY THIS
- CanardPortID port_id; ///< Read-only DO NOT MODIFY THIS
-
- /// This field can be arbitrarily mutated by the user. It is never accessed by the library.
- /// Its purpose is to simplify integration with OOP interfaces.
- void* user_reference;
-
- /// The current architecture is an acceptable middle ground between worst-case execution time and memory
- /// consumption. Instead of statically pre-allocating a dedicated RX session for each remote node-ID here in
- /// this table, we only keep pointers, which are NULL by default, populating a new RX session dynamically
- /// on an ad-hoc basis when we first receive a transfer from that node. This is O(1) because our memory
- /// allocation routines are assumed to be O(1) and we make at most one allocation per remote node.
- ///
- /// A more predictable and simpler approach is to pre-allocate states here statically instead of keeping
- /// just pointers, but it would push the size of this instance from about 0.5 KiB to ~3 KiB for a typical 32-bit
- /// system. Since this is a general-purpose library, we have to pick a middle ground so we use the more complex
- /// but more memory-efficient approach.
- struct CanardInternalRxSession* sessions[CANARD_NODE_ID_MAX + 1U]; ///< Read-only DO NOT MODIFY THIS
+ void* user_context;
};
-/// Reassembled incoming transfer returned by canardRxAccept().
-struct CanardRxTransfer
+typedef struct canard_vtable_t
{
- struct CanardTransferMetadata metadata;
-
- /// The timestamp of the first received CAN frame of this transfer.
- /// The time system may be arbitrary as long as the clock is monotonic (steady).
- CanardMicrosecond timestamp_usec;
-
- /// The application is required to deallocate the payload after the transfer is processed.
- struct CanardMutablePayload payload;
-};
-
-/// This is the core structure that keeps all of the states and allocated resources of the library instance.
-struct CanardInstance
+ /// The current monotonic time in microseconds. Must be a non-negative non-decreasing value.
+ canard_us_t (*now)(const canard_t*);
+
+ /// Submit one CAN frame for transmission via the specified interface.
+ /// If the data is empty (size==0), the data pointer may be NULL.
+ /// Returns true if the frame was accepted for transmission, false if there is no free mailbox (try again later).
+ /// The callback must not mutate the TX pipeline (no publish/cancel/free/etc).
+ /// If the can_data needs to be retained for later retransmission, use canard_refcount_inc()/canard_refcount_dec().
+ bool (*tx)(canard_t*,
+ void* user_context,
+ canard_us_t deadline,
+ uint_least8_t iface_index,
+ bool fd,
+ uint32_t extended_can_id,
+ canard_bytes_t can_data);
+
+ /// Reconfigure the acceptance filters of the CAN controller hardware.
+ /// The prior configuration, if any, is replaced entirely.
+ /// filter_count is guaranteed to not exceed the value given at initialization.
+ /// This function may be NULL if the CAN controller/driver does not support filtering or it is not desired.
+ /// This function is only invoked from canard_poll().
+ /// Returns true on success, false on failure.
+ bool (*filter)(canard_t*, size_t filter_count, const canard_filter_t* filters);
+} canard_vtable_t;
+
+/// Main instance object. Usage: new -> subscribe/publish/ingest/poll -> unsubscribe/destroy.
+/// Dominant costs are log-time tree operations plus work linear in the number of CAN frames in a transfer.
+/// Heap use scales with queued TX transfers/frames and active RX sessions/reassembly slots, not bus history.
+/// None of the fields should be mutated by the application, unless explicitly allowed.
+struct canard_t
{
- /// User pointer that can link this instance with other objects.
- /// This field can be changed arbitrarily, the library does not access it after initialization.
- /// The default value is NULL.
- void* user_reference;
-
- /// The node-ID of the local node.
- /// Per the Cyphal Specification, the node-ID should not be assigned more than once.
- /// Invalid values are treated as CANARD_NODE_ID_UNSET. The default value is CANARD_NODE_ID_UNSET.
- CanardNodeID node_id;
-
- /// Dynamic memory management callbacks. See their type documentation for details.
- /// They SHALL be valid function pointers at all times.
- /// The time complexity models given in the API documentation are made on the assumption that the memory management
- /// functions have constant complexity O(1).
- ///
- /// The following API functions may allocate memory: canardTxPush(), canardRxAccept().
- /// The following API functions may deallocate memory: canardTxPush(), canardTxFree(), canardTxPoll(),
- /// canardRxAccept(), canardRxSubscribe(), canardRxUnsubscribe().
- /// The exact memory requirement and usage model is specified for each function in its documentation.
- struct CanardMemoryResource memory;
-
- /// Read-only DO NOT MODIFY THIS
- struct CanardTreeNode* rx_subscriptions[CANARD_NUM_TRANSFER_KINDS];
+ uint64_t node_id_occupancy_bitmap[2];
+
+ /// By default, the node-ID is allocated automatically, with occupancy/collision tracking.
+ /// Automatic allocation will avoid using the node-ID of zero to ensure compatibility with legacy v0 nodes, where
+ /// zero is reserved for anonymous nodes. Zero can still be assigned manually if compatibility is not needed.
+ /// The node-ID can be set manually via the corresponding function.
+ uint_least8_t node_id;
+
+ struct
+ {
+ /// By default, CAN FD mode is used; this flag can be used to change the mode to Classic CAN if needed;
+ /// for example, if the local CAN controller does not support CAN FD, or if the remote nodes do not support it.
+ /// The flag can be switched at any time. All redundant interfaces share the same mode.
+ ///
+ /// A valid auto-configuration strategy that could be implemented in the application is to start in FD mode
+ /// and switch to Classic if a non-FD frame is observed on the bus.
+ ///
+ /// The local node can accept both Classic CAN and CAN FD frames regardless of this setting;
+ /// the setting only affects the mode used for outgoing frames.
+ ///
+ /// Legacy v0 transfers (UAVCAN/DroneCAN) are always sent in Classic CAN mode regardless of this flag,
+ /// because UAVCAN v0 does not define CAN FD support. CAN FD v0 transfers can still be received though.
+ bool fd;
+
+ /// Queue size and capacity are measured in CAN frames for convenience, but the TX pipeline actually operates
+ /// on whole transfers for efficiency. The number of enqueued frames is a pretty much synthetic metric for
+ /// convenience, that is derived from the number of enqueued transfers and their sizes.
+ size_t queue_capacity;
+ size_t queue_size;
+
+ /// Incremented with every enqueued transfer. Used internally but also works as a stats counter.
+ uint64_t seqno;
+
+ canard_tree_t* pending[CANARD_IFACE_COUNT]; ///< Next to transmit on the left.
+ canard_tree_t* deadline; ///< Soonest to expire on the left.
+ canard_list_t agewise; ///< ALL transfers FIFO, oldest at the head.
+ } tx;
+
+ struct
+ {
+ canard_tree_t* subscriptions[CANARD_KIND_COUNT];
+ canard_list_t list_session_by_animation; ///< Oldest at the head.
+ size_t filter_count;
+ bool filters_dirty; ///< Set when subscribed/unsubscribed or node-ID is changed.
+ } rx;
+
+ /// Error counters incremented automatically when the corresponding error condition occurs.
+ /// These counters are never decremented by the library but they can be reset by the application if needed.
+ struct
+ {
+ uint64_t oom; ///< Out of memory; a transfer could have been lost.
+ uint64_t tx_capacity; ///< A transfer could not be enqueued due to queue capacity limit.
+ uint64_t tx_sacrifice; ///< An old pending transfer had to be sacrificed to make room for a new transfer.
+ uint64_t tx_expiration; ///< A transfer had to be dequeued due to deadline expiration.
+ uint64_t rx_frame; ///< A received frame was malformed and thus dropped.
+ uint64_t rx_transfer; ///< A transfer could not be reassembled correctly.
+ uint64_t collision; ///< Number of times the local node-ID was changed to repair a collision.
+ } err;
+
+ canard_mem_set_t mem;
+ uint64_t prng_state;
+
+ const canard_vtable_t* vtable;
+
+ void* user_context;
};
-/// CAN acceptance filter configuration with an extended 29-bit ID utilizing an ID + mask filter scheme.
-/// Filter configuration can be programmed into a CAN controller to filter out irrelevant messages in hardware.
-/// This allows the software application to reduce CPU load spent on processing irrelevant messages.
-struct CanardFilter
-{
- /// 29-bit extended ID. Defines the extended CAN ID to filter incoming frames against.
- /// The bits above 29-th shall be zero.
- uint32_t extended_can_id;
- /// 29-bit extended mask. Defines the bitmask used to enable/disable bits used to filter messages.
- /// Only bits that are enabled are compared to the extended_can_id for filtering.
- /// The bits above 29-th shall be zero.
- uint32_t extended_mask;
-};
-
-/// Construct a new library instance.
-/// The default values will be assigned as specified in the structure field documentation.
-/// If any of the memory resource pointers are NULL, the behavior is undefined.
-///
-/// The instance does not hold any resources itself except for the allocated memory.
-/// To safely discard it, simply remove all existing subscriptions, and don't forget about the TX queues.
-///
-/// The time complexity is constant. This function does not invoke the dynamic memory manager.
-struct CanardInstance canardInit(const struct CanardMemoryResource memory);
-
-/// Construct a new transmission queue instance with the specified values for capacity and mtu_bytes.
-/// No memory allocation is going to take place until the queue is actually pushed to.
-/// Applications are expected to have one instance of this type per redundant interface.
-///
-/// The instance does not hold any resources itself except for the allocated memory.
-/// To safely discard it, simply pop all items from the queue and free them.
-///
-/// The time complexity is constant. This function does not invoke the dynamic memory manager.
-struct CanardTxQueue canardTxInit(const size_t capacity,
- const size_t mtu_bytes,
- const struct CanardMemoryResource memory);
-
-/// This function serializes a transfer into a sequence of transport frames and inserts them into the prioritized
-/// transmission queue at the appropriate position. Afterwards, the application is supposed to take the enqueued frames
-/// from the transmission queue using the function canardTxPeek() and transmit them. Each transmitted (or otherwise
-/// discarded, e.g., due to timeout) frame should be removed from the queue using canardTxPop(). The queue is
-/// prioritized following the normal CAN frame arbitration rules to avoid the inner priority inversion. The transfer
-/// payload will be copied into the transmission queue so that the lifetime of the frames is not related to the
-/// lifetime of the input payload buffer.
-///
-/// The MTU of the generated frames is dependent on the value of the MTU setting at the time when this function
-/// is invoked. The MTU setting can be changed arbitrarily between invocations.
-///
-/// The tx_deadline_usec will be used to populate the timestamp values of the resulting transport
-/// frames (so all frames will have the same timestamp value). This feature is intended to facilitate transmission
-/// deadline tracking, i.e., aborting frames that could not be transmitted before the specified deadline.
-/// Therefore, normally, the timestamp value should be in the future.
-/// The library compares (now>deadline) to determine which frames timed out, and so could
-/// be dropped (incrementing frames_expired, unless NULL).
-/// If this timeout behavior is not needed, pass now_usec=0 to canardTxPush()/canardTxPoll().
-///
-/// The described above automatic dropping of timed-out frames was added in the v4 of the library as an optional
-/// feature. It is applied only to the frames that are already in the TX queue (not the new ones that are being pushed
-/// in this call). The feature can be disabled by passing zero time in the now_usec parameter,
-/// so that it will be up to the application to track the tx_deadline_usec (see canardTxPeek).
-///
-/// The function returns the number of frames enqueued into the prioritized TX queue (which is always a positive
-/// number) in case of success (so that the application can track the number of items in the TX queue if necessary).
-/// In case of failure, the function returns a negated error code: either invalid argument or out-of-memory.
-///
-/// An invalid argument error may be returned in the following cases:
-/// - Any of the input arguments are NULL.
-/// - The remote node-ID is not CANARD_NODE_ID_UNSET and the transfer is a message transfer.
-/// - The remote node-ID is above CANARD_NODE_ID_MAX and the transfer is a service transfer.
-/// - The priority, subject-ID, or service-ID exceed their respective maximums.
-/// - The transfer kind is invalid.
-/// - The payload pointer is NULL while the payload size is nonzero.
-/// - The local node is anonymous and a message transfer is requested that requires a multi-frame transfer.
-/// - The local node is anonymous and a service transfer is requested.
-/// The following cases are handled without raising an invalid argument error:
-/// - If the transfer-ID is above the maximum, the excessive bits are silently masked away
-/// (i.e., the modulo is computed automatically, so the caller doesn't have to bother).
-///
-/// An out-of-memory error is returned if a TX frame could not be allocated due to the memory being exhausted,
-/// or if the capacity of the queue would be exhausted by this operation. In such cases, all frames allocated for
-/// this transfer (if any) will be deallocated automatically. In other words, either all frames of the transfer are
-/// enqueued successfully, or none are.
-///
-/// The time complexity is O(p + log e), where p is the amount of payload in the transfer, and e is the number of
-/// frames already enqueued in the transmission queue.
-///
-/// The memory allocation requirement is two allocations per transport frame. A single-frame transfer takes two
-/// allocations; a multi-frame transfer of N frames takes N*2 allocations. In each pair of allocations:
-/// - the first allocation is for CanardTxQueueItem; the size is sizeof(CanardTxQueueItem);
-/// the Canard instance memory resource is used for this allocation (and later for deallocation);
-/// - the second allocation is for payload storage (the frame data) - size is normally MTU but could be less for
-/// the last frame of the transfer; the TX queue memory resource is used for this allocation.
-int32_t canardTxPush(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond tx_deadline_usec,
- const struct CanardTransferMetadata* const metadata,
- const struct CanardPayload payload,
- const CanardMicrosecond now_usec,
- uint64_t* const frames_expired);
-
-/// This function accesses the top element of the prioritized transmission queue. The queue itself is not modified
-/// (i.e., the accessed element is not removed). The application should invoke this function to collect the transport
-/// frames of serialized transfers pushed into the prioritized transmission queue by canardTxPush().
-///
-/// The timestamp values of returned frames are initialized with tx_deadline_usec from canardTxPush().
-/// Timestamps are used to specify the transmission deadline. It is up to the application and/or the media layer
-/// to implement the discardment of timed-out transport frames. The library does not check it in this call,
-/// so a frame that is already timed out may be returned here.
-///
-/// If the queue is empty or if the argument is NULL, the returned value is NULL.
-///
-/// If the queue is non-empty, the returned value is a pointer to its top element (i.e., the next frame to transmit).
-/// The returned pointer points to an object allocated in the dynamic storage; it should be eventually freed by the
-/// application by calling canardTxFree. The memory shall not be freed before the entry is removed
-/// from the queue by calling canardTxPop(); this is because until canardTxPop() is executed, the library retains
-/// ownership of the object. The pointer retains validity until explicitly freed by the application; in other words,
-/// calling canardTxPop() does not invalidate the object.
-///
-/// The payload buffer is allocated in the memory resource of the queue. The application may transfer ownership of
-/// the payload to a different application component (e.g., to the transmission media) by copying the pointer and then
-/// (if the ownership transfer is accepted) by nullifying the payload fields of the frame (data & allocated_size).
-/// If these fields stay with their original values, the canardTxFree (after proper canardTxPop of course) will
-/// deallocate the payload buffer. In any case, the payload has to be eventually deallocated by the TX queue memory
-/// resource. It will be automatically done by canardTxFree() (if the payload stays in the item);
-/// if moved, it is the responsibility of the application to eventually (e.g., at the end of transmission)
-/// deallocate the memory with TX queue memory resource. Note that the mentioned above nullification of the payload
-/// fields is the only reason why a returned TX item pointer is mutable.
-///
-/// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager.
-struct CanardTxQueueItem* canardTxPeek(const struct CanardTxQueue* const que);
-
-/// This function transfers the ownership of the specified element of the prioritized transmission queue from the queue
-/// to the application. The element does not necessarily need to be the top one -- it is safe to dequeue any element.
-/// The element is dequeued but not invalidated; it is the responsibility of the application to deallocate the
-/// memory used by the object later (use canardTxFree helper). The memory SHALL NOT be deallocated UNTIL this function
-/// is invoked. The function returns the same pointer that it is given.
-///
-/// If any of the arguments are NULL, the function has no effect and returns NULL.
-///
-/// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager.
-struct CanardTxQueueItem* canardTxPop(struct CanardTxQueue* const que, struct CanardTxQueueItem* const item);
-
-/// This is a helper that frees the memory allocated (from the instance memory) for the item,
-/// as well as the internal frame payload buffer (if any) associated with it (using TX queue memory).
-/// If the item argument is NULL, the function has no effect. The time complexity is constant.
-/// If the item frame payload is NULL then it is assumed that the payload buffer was already freed,
-/// or moved to a different owner (e.g., to the media layer).
-void canardTxFree(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- struct CanardTxQueueItem* const item);
-
-/// This is a helper that combines several Canard TX calls (canardTxPeek, canardTxPop and canardTxFree)
-/// into one "polling" algorithm. It simplifies the whole process of transmitting frames to just two function calls:
-/// - canardTxPush() to enqueue frames.
-/// - canardTxPoll() to dequeue, transmit, and free frames one-by-one.
-///
-/// The algorithm implements a typical pattern of de-queuing, transmitting and freeing a TX queue item,
-/// as well as handling transmission failures, retries, and deadline timeouts.
-/// The function is intended to be periodically called whenever a free TX slot appears in the CAN controller.
-///
-/// The current time is used to determine if the frame has timed out. Use zero value to disable automatic dropping
-/// of timed-out frames. Frames that have been removed due to timeout increment frames_expired, unless NULL.
-///
-/// If at least one frame of a transfer fails to transmit (handler returns error), all frames of the transfer are
-/// removed from the queue and *frames_failed is incremented accordingly, unless NULL.
-///
-/// The user reference will be passed to the frame handler (see CanardTxFrameHandler).
-///
-/// The return value is zero if the queue is empty,
-/// or -CANARD_ERROR_INVALID_ARGUMENT if any of the arguments are invalid.
-/// Otherwise, the value is forwarded from the last frame handler call (see CanardTxFrameHandler).
-int8_t canardTxPoll(struct CanardTxQueue* const que,
- const struct CanardInstance* const ins,
- const CanardMicrosecond now_usec,
- void* const user_reference,
- const CanardTxFrameHandler frame_handler,
- uint64_t* const frames_expired,
- uint64_t* const frames_failed);
-
-/// This function implements the transfer reassembly logic. It accepts a transport frame from any of the redundant
-/// interfaces, locates the appropriate subscription state, and, if found, updates it. If the frame completed a
-/// transfer, the return value is 1 (one) and the out_transfer pointer is populated with the parameters of the
-/// newly reassembled transfer. The transfer reassembly logic is defined in the Cyphal specification.
-///
-/// The MTU of the accepted frame can be arbitrary; that is, any MTU is accepted. The DLC validity is irrelevant.
-///
-/// Any value of redundant_iface_index is accepted; that is, up to 256 redundant interfaces are supported.
-/// The index of the interface from which the transfer is accepted is always the same as redundant_iface_index
-/// of the current invocation, so the application can always determine which interface has delivered the transfer.
-///
-/// Upon return, the out_subscription pointer will point to the instance of CanardRxSubscription that accepted this
-/// frame; if no matching subscription exists (i.e., frame discarded), the pointer will be NULL.
-/// If this information is not relevant, set out_subscription to NULL.
-/// The purpose of this argument is to allow integration with OOP adapters built on top of libcanard; see also the
-/// user_reference provided in CanardRxSubscription.
-///
-/// The function invokes the dynamic memory manager in the following cases only:
-///
-/// 1. New memory for a session state object is allocated when a new session is initiated.
-/// This event occurs when a transport frame that matches a known subscription is received from a node that
-/// did not emit matching frames since the subscription was created.
-/// Once a new session is created, it is not destroyed until the subscription is terminated by invoking
-/// canardRxUnsubscribe(). The number of sessions is bounded and the bound is low (at most the number of nodes
-/// in the network minus one), also the size of a session instance is very small, so the removal is unnecessary.
-/// Real-time networks typically do not change their configuration at runtime, so it is possible to reduce
-/// the time complexity by never deallocating sessions.
-/// The size of a session instance is at most 48 bytes on any conventional platform (typically much smaller).
-///
-/// 2. New memory for the transfer payload buffer is allocated when a new transfer is initiated, unless the buffer
-/// was already allocated at the time.
-/// This event occurs when a transport frame that matches a known subscription is received and it begins a
-/// new transfer (that is, the start-of-frame flag is set and it is not a duplicate).
-/// The amount of the allocated memory equals the extent as configured via canardRxSubscribe(); please read
-/// its documentation for further information about the extent and related edge cases.
-/// The worst case occurs when every node on the bus initiates a multi-frame transfer for which there is a
-/// matching subscription: in this case, the library will allocate number_of_nodes allocations, where each
-/// allocation is the same size as the configured extent.
-///
-/// 3. Memory allocated for the transfer payload buffer may be deallocated at the discretion of the library.
-/// This operation does not increase the worst case execution time and does not improve the worst case memory
-/// consumption, so a deterministic application need not consider this behavior in the resource analysis.
-/// This behavior is implemented for the benefit of applications where rigorous characterization is unnecessary.
-///
-/// The worst case dynamic memory consumption per subscription is:
-///
-/// (sizeof(session instance) + extent) * number_of_nodes
-///
-/// Where sizeof(session instance) and extent are defined above, and number_of_nodes is the number of remote
-/// nodes emitting transfers that match the subscription (which cannot exceed (CANARD_NODE_ID_MAX-1) by design).
-/// If the dynamic memory pool is sized correctly, the application is guaranteed to never encounter an
-/// out-of-memory (OOM) error at runtime. The actual size of the dynamic memory pool is typically larger;
-/// for a detailed treatment of the problem and the related theory please refer to the documentation of O1Heap --
-/// a deterministic memory allocator for hard real-time embedded systems.
-///
-/// The time complexity is O(p + log n) where n is the number of subject-IDs or service-IDs subscribed to by the
-/// application, depending on the transfer kind of the supplied frame, and p is the amount of payload in the received
-/// frame (because it will be copied into an internal contiguous buffer). Observe that the time complexity is
-/// invariant to the network configuration (such as the number of online nodes) -- this is a very important
-/// design guarantee for real-time applications because the execution time is dependent only on the number of
-/// active subscriptions for a given transfer kind, and the MTU, both of which are easy to predict and account for.
-/// Excepting the subscription search and the payload data copying, the entire RX pipeline contains neither loops
-/// nor recursion.
-/// Misaddressed and malformed frames are discarded in constant time.
-///
-/// The function returns 1 (one) if the new frame completed a transfer. In this case, the details of the transfer
-/// are stored into out_transfer, and the transfer payload buffer ownership is passed to that object. The lifetime
-/// of the resulting transfer object is not related to the lifetime of the input transport frame (that is, even if
-/// it is a single-frame transfer, its payload is copied out into a new dynamically allocated buffer storage).
-/// If the extent is zero, the payload pointer may be NULL, since there is no data to store and so a
-/// buffer is not needed. The application is responsible for deallocating the payload buffer when the processing
-/// is done by invoking memory_free on the transfer payload pointer.
-///
-/// The function returns a negated out-of-memory error if it was unable to allocate dynamic memory.
-///
-/// The function does nothing and returns a negated invalid argument error immediately if any condition is true:
-/// - Any of the input arguments that are pointers are NULL.
-/// - The payload pointer of the input frame is NULL while its size is non-zero.
-/// - The CAN ID of the input frame is not less than 2**29=0x20000000.
-///
-/// The function returns zero if any of the following conditions are true (the general policy is that protocol
-/// errors are not escalated because they do not construe a node-local error):
-/// - The received frame is not a valid Cyphal/CAN transport frame.
-/// - The received frame is a valid Cyphal/CAN transport frame, but there is no matching subscription,
-/// the frame did not complete a transfer, the frame forms an invalid frame sequence, the frame is a duplicate,
-/// the frame is unicast to a different node (address mismatch).
-int8_t canardRxAccept(struct CanardInstance* const ins,
- const CanardMicrosecond timestamp_usec,
- const struct CanardFrame* const frame,
- const uint8_t redundant_iface_index,
- struct CanardRxTransfer* const out_transfer,
- struct CanardRxSubscription** const out_subscription);
-
-/// This function creates a new subscription, allowing the application to register its interest in a particular
-/// category of transfers. The library will reject all transport frames for which there is no active subscription.
-/// The reference out_subscription shall retain validity until the subscription is terminated (the referred object
-/// cannot be moved or destroyed).
-///
-/// If such subscription already exists, it will be removed first as if canardRxUnsubscribe() was
-/// invoked by the application, and then re-created anew with the new parameters.
-///
-/// The extent defines the size of the transfer payload memory buffer; or, in other words, the maximum possible size
-/// of received objects, considering also possible future versions with new fields. It is safe to pick larger values.
-/// Note well that the extent is not the same thing as the maximum size of the object, it is usually larger!
-/// Transfers that carry payloads that exceed the specified extent will be accepted anyway but the excess payload
-/// will be truncated away, as mandated by the Specification. The transfer CRC is always validated regardless of
-/// whether its payload is truncated.
-///
-/// The default transfer-ID timeout value is defined as CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC; use it if not sure.
-/// The redundant interface fail-over timeout (if redundant interfaces are used) is the same as the transfer-ID timeout.
-/// It may be reduced in a future release of the library, but it will not affect the backward compatibility.
-///
-/// The return value is 1 if a new subscription has been created as requested.
-/// The return value is 0 if such subscription existed at the time the function was invoked. In this case,
-/// the existing subscription is terminated and then a new one is created in its place. Pending transfers may be lost.
-/// The return value is a negated invalid argument error if any of the input arguments are invalid.
-///
-/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind.
-/// This function does not allocate new memory. The function may deallocate memory if such subscription already
-/// existed; the deallocation behavior is specified in the documentation for canardRxUnsubscribe().
-///
-/// Subscription instances have large look-up tables to ensure that the temporal properties of the algorithms are
-/// invariant to the network configuration (i.e., a node that is validated on a network containing one other node
-/// will provably perform identically on a network that contains X nodes). This is a conscious time-memory trade-off.
-int8_t canardRxSubscribe(struct CanardInstance* const ins,
- const enum CanardTransferKind transfer_kind,
- const CanardPortID port_id,
- const size_t extent,
- const CanardMicrosecond transfer_id_timeout_usec,
- struct CanardRxSubscription* const out_subscription);
-
-/// This function reverses the effect of canardRxSubscribe().
-/// If the subscription is found, all its memory is de-allocated (session states and payload buffers); to determine
-/// the amount of memory freed, please refer to the memory allocation requirement model of canardRxAccept().
-///
-/// The return value is 1 if such subscription existed (and, therefore, it was removed).
-/// The return value is 0 if such subscription does not exist. In this case, the function has no effect.
-/// The return value is a negated invalid argument error if any of the input arguments are invalid.
-///
-/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind.
-/// This function does not allocate new memory.
-int8_t canardRxUnsubscribe(struct CanardInstance* const ins,
- const enum CanardTransferKind transfer_kind,
- const CanardPortID port_id);
-
-/// This function allows to check the effect of canardRxSubscribe() and canardRxUnsubscribe().
-///
-/// The return value is 1 if the specified subscription exists, 0 otherwise.
-/// The return value is a negated invalid argument error if any of the input arguments are invalid.
-/// Output out_subscription could be NULL, but if it is not, it will be populated with the pointer to the existing
-/// subscription. In case the subscription does not exist (or error), out_subscription won't be touched.
-/// Result pointer to the subscription is valid until the subscription is terminated.
-///
-/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind.
-/// This function does not allocate new memory.
-int8_t canardRxGetSubscription(const struct CanardInstance* const ins,
- const enum CanardTransferKind transfer_kind,
- const CanardPortID port_id,
- struct CanardRxSubscription** const out_subscription);
-
-/// Utilities for generating CAN controller hardware acceptance filter configurations
-/// to accept specific subjects, services, or nodes.
-///
-/// Complex applications will likely subscribe to more subject IDs than there are
-/// acceptance filters available in the CAN hardware. In this case, the application
-/// should implement filter consolidation. See canardConsolidateFilters()
-/// as well as the Cyphal specification for details.
-
-/// Generate an acceptance filter configuration to accept a specific subject ID.
-struct CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id);
-
-/// Generate an acceptance filter configuration to accept both requests and responses for a specific service.
-///
-/// Users may prefer to instead use a catch-all acceptance filter configuration for accepting
-/// all service requests and responses targeted at the specified local node ID.
-/// See canardMakeFilterForServices() for this.
-struct CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id);
-
-/// Generate an acceptance filter configuration to accept all service
-/// requests and responses targeted to the specified local node ID.
-///
-/// Due to the relatively low frequency of service transfers expected on a network,
-/// and the fact that a service directed at a specific node is not likely to be rejected by that node,
-/// a user may prefer to use this over canardMakeFilterForService()
-/// in order to simplify the API usage and reduce the number of required hardware CAN acceptance filters.
-struct CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id);
-
-/// Consolidate two acceptance filter configurations into a single configuration.
-///
-/// Complex applications will likely subscribe to more subject IDs than there are
-/// acceptance filters available in the CAN hardware. In this case, the application
-/// should implement filter consolidation. While this may make it impossible to create
-/// a 'perfect' filter that only accepts desired subject IDs, the application should apply
-/// consolidation in a manner that minimizes the number of undesired messages that pass
-/// through the hardware acceptance filters and require software filtering (implemented by canardRxSubscribe).
-///
-/// While optimal choice of filter consolidation is a function of the number of available hardware filters,
-/// the set of transfers needed by the application, and the expected frequency of occurrence
-/// of all possible distinct transfers on the bus, it is possible to generate a quasi-optimal configuration
-/// if information about the frequency of occurrence of different transfers is not known.
-/// For details, see the "Automatic hardware acceptance filter configuration" note under the Cyphal/CAN section
-/// in the Transport Layer chapter of the Cyphal specification.
-struct CanardFilter canardConsolidateFilters(const struct CanardFilter* const a, const struct CanardFilter* const b);
+/// The TX queue is shared between all redundant interfaces with deduplication (each frame is enqueued only once).
+/// The capacity set here is therefore the total capacity across all interfaces.
+///
+/// The PRNG seed must be likely to be distinct per node on the network; it may be a constant value.
+/// In the absence of a true RNG, a good way to obtain the seed is to use a unique hardware identifier hashed
+/// down to 64 bits with a good hash, e.g., rapidhash.
+///
+/// The local node-ID will be chosen randomly by default, and the stack will monitor the network for node-ID occupancy
+/// and collisions, and will automatically migrate to a free node-ID shall a collision be detected.
+/// If manual allocation is desired, use the corresponding function to set the node-ID after initialization.
+///
+/// The filter count is the number of CAN acceptance filters that the stack can utilize. It is possible to pass zero
+/// filters if filtering is unneeded/unsupported. When the number of active subscriptions exceeds the number of
+/// available filters, filter coalescence is performed, which however has a high complexity bound; it is thus
+/// recommended that the number of filters is either large enough to accommodate all subscriptions,
+/// or small enough in the single digits where the coalescence load remains low. The filter configuration is
+/// recomputed and applied on every poll() following a change in the subscription set or local node-ID.
+///
+/// Steady-state heap use is O(queued TX transfers + queued TX frames + active RX sessions + RX slots).
+/// Each RX slot is bounded by the subscription extent; filter recomputation may dominate only if coalescence is needed.
+///
+/// CAN FD mode is selected by default for outgoing frames; override the fd flag to change the mode if needed.
+///
+/// Returns true on success, false if any of the parameters are invalid.
+bool canard_new(canard_t* const self,
+ const canard_vtable_t* const vtable,
+ const canard_mem_set_t memory,
+ const size_t tx_queue_capacity,
+ const uint64_t prng_seed,
+ const size_t filter_count);
+
+/// The application MUST destroy all subscriptions before invoking this (this is asserted).
+/// The application MUST also release all retained TX frame views before invoking this.
+/// The TX queue will be purged automatically if not empty.
+void canard_destroy(canard_t* const self);
+
+/// This can be invoked after initialization to manually assign the desired node-ID.
+/// This does not disable the occupancy/collision monitoring; the assigned ID will be changed if a collision is found.
+/// Started multi-frame TX continuations are canceled and filter reconfiguration is scheduled at next canard_poll().
+/// Anonymous node-ID is not allowed. Zero is fine only if compatibility with legacy protocol is not needed.
+/// Returns false if any of the arguments are invalid.
+bool canard_set_node_id(canard_t* const self, const uint_least8_t node_id);
+
+/// This must be invoked periodically to ensure liveliness.
+/// The function must be called asap once any of the interfaces for which there are pending outgoing transfers
+/// become writable, and not less frequently than once in a few milliseconds. The invocation rate defines the
+/// resolution of deadline handling.
+/// Work is proportional to expired/pending TX work; dirty RX filters may add subscription-dependent one-time cost.
+/// This is also where deferred hardware filter reconfiguration is attempted.
+void canard_poll(canard_t* const self, const uint_least8_t tx_ready_iface_bitmap);
+
+/// Returns a bitmap of interfaces that have pending transmissions. This is useful for IO multiplexing.
+uint_least8_t canard_pending_ifaces(const canard_t* const self);
+
+/// True if successfully processed, false if any of the arguments are invalid.
+/// Other failures are reported via the counters.
+/// This function should not be invoked from the callbacks.
+/// Subscription callbacks may run synchronously before this function returns.
+/// The lifetime of can_data can end after this function returns.
+/// Dominant steady-state cost is log-time subscription/session lookup;
+/// RX memory is allocated only when new state is needed, and multi-frame payload ownership is transferred via origin.
+bool canard_ingest_frame(canard_t* const self,
+ const canard_us_t timestamp,
+ const uint_least8_t iface_index,
+ const uint32_t extended_can_id,
+ const canard_bytes_t can_data);
+
+/// Retain a TX frame view obtained from tx() so it may outlive the callback and the TX queue entry.
+/// The retained view must be released before canard_destroy() is invoked on the owning instance.
+/// This is not applicable to RX payload views.
+void canard_refcount_inc(const canard_bytes_t obj);
+
+/// Release a TX frame retained earlier. self shall own the underlying tx_frame resource.
+/// This is not applicable to RX payload views.
+void canard_refcount_dec(canard_t* const self, const canard_bytes_t obj);
+
+/// Enqueue a message transfer on the specified interfaces. Use CANARD_IFACE_BITMAP_ALL to send on all interfaces.
+/// Message ordering observed on the bus is guaranteed per subject as long as the priority of later messages is
+/// not higher (numerically not lower) than that of earlier messages.
+/// The context is passed into the tx() vtable function.
+///
+/// Cost is roughly linear in the number of emitted CAN frames plus log-time queue indexing.
+/// Memory use is one TX transfer object plus one shared TX frame object per emitted CAN frame.
+///
+/// Returns true on success; false on invalid arguments, OOM, or TX queue exhaustion.
+/// See err.oom and err.tx_capacity for the enqueue failure cause.
+bool canard_publish_16b(canard_t* const self,
+ const canard_us_t deadline,
+ const uint_least8_t iface_bitmap,
+ const canard_prio_t priority,
+ const uint16_t subject_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+bool canard_publish_13b(canard_t* const self,
+ const canard_us_t deadline,
+ const uint_least8_t iface_bitmap,
+ const canard_prio_t priority,
+ const uint16_t subject_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+
+/// Enqueue a service request on all ifaces; other semantics, failure modes, and memory model match canard_publish().
+bool canard_request(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint16_t service_id,
+ const uint_least8_t server_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+
+/// Enqueue a service response on all ifaces; other semantics, failure modes, and memory model match canard_publish().
+bool canard_respond(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint16_t service_id,
+ const uint_least8_t client_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+
+/// Register a new subscription on a subject with 13-bit or 16-bit ID.
+/// There may be at most one subscription per subject-ID under each ID size; IDs of different sizes do not collide.
+/// The subscription instance must not be moved while in use.
+///
+/// The extent specifies the maximum message size that can be received from the subject; longer messages will be
+/// truncated per the implicit truncation rule (see the Spec).
+/// Subscription updates are log-time; per-remote RX session state is allocated lazily on demand.
+///
+/// Returns true on success, false if any of the arguments are invalid or if there is already a subscription for the
+/// given subject-ID.
+bool canard_subscribe_16b(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t subject_id,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable);
+bool canard_subscribe_13b(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t subject_id, // [0,8191]
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable);
+
+/// Unicast transfers in Cyphal/CAN v1.1 are supposed to be modeled as requests to service-ID 511, with a 128-element
+/// array of transfer-ID counters, one per remote. Some large nonzero transfer-ID timeout is required to satisfy the
+/// deduplication requirement. This is outside of the scope of this library so it's not implemented here.
+/// There may be at most one request subscription per service-ID.
+/// Subscription updates are log-time; per-remote RX session state is allocated lazily on demand.
+bool canard_subscribe_request(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t service_id,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable);
+
+/// There may be at most one response subscription per service-ID.
+/// Response transfers necessarily have a zero transfer-ID timeout: https://github.com/OpenCyphal/libcanard/issues/247.
+/// Subscription updates are log-time; per-remote RX session state is allocated lazily on demand.
+bool canard_subscribe_response(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t service_id,
+ const size_t extent,
+ const canard_subscription_vtable_t* const vtable);
+
+/// This can be used to undo all kinds of subscriptions, incl. v0.
+/// Complexity is log-time in the subscription set plus linear in the number of remote sessions owned by it.
+void canard_unsubscribe(canard_t* const self, canard_subscription_t* const subscription);
+
+// --------------------------------- UAVCAN v0 & DroneCAN legacy compatibility API ---------------------------------
+
+/// ATTENTION: Due to the v0 design, the problem of protocol version detection for correct frame parsing given
+/// multi-frame transfers is undecidable without imposing constraints on the network configuration.
+///
+/// The core problem is that the protocol version is encoded in the initial state of the toggle bit, which is
+/// by definition only observable in the first frame of a transfer; if there happen to be concurrent multi-frame
+/// transfers emitted by the same node under the same transfer-ID under different versions, and their port-IDs
+/// (and in the case of service transfers also the destination node-IDs, with a 1-bit bias) happen to alias
+/// pathologically, remote subscribers will observe the two frame sequences as belonging to the same transfer.
+///
+/// Various heuristics exist, but due to intricate edge cases no robust solution exists for the general case.
+/// The recommended solution is to adopt at least one of the following constraints on the network configuration:
+///
+/// - A single node-ID can only emit transfers of any single protocol version. The disambiguation problem is addressed
+/// by the fact that the multi-frame reassembly state machine necessarily indexes states by the remote node-ID
+/// (this is not an implementation detail but a requirement from the Specification of both UAVCAN v0 and Cyphal/CAN).
+/// The first frame of any transfer is only accepted if the protocol version matches (it is observable reliably
+/// in this case); subsequent frames even if aliased will not cause data corruption because without the start frame
+/// the transfer will not be accepted. An application may maintain more than one node-ID with multiple canard_t.
+///
+/// - A single node-ID may emit transfers of both versions simultaneously as long as the resulting CAN IDs do not alias.
+/// For example, if a v0 data type ID is chosen such that it maps a 1-bit onto a reserved 0-bit of the v1 CAN ID,
+/// no ambiguity will occur.
+///
+/// The above concerns only data emission. It is always safe to receive transfers of any version from any node as long
+/// as the above emission constraints are satisfied.
+
+/// The legacy UAVCAN v0 protocol has 5-bit priority, which is obtained from 3-bit priority by left-shifting.
+///
+/// All legacy transfers are always sent in Classic CAN mode regardless of the FD flag.
+///
+/// To obtain the CRC seed, use canard_v0_crc_seed_from_data_type_signature(); if the payload does not exceed 7 bytes,
+/// the CRC seed can be arbitrary since it is not needed for single-frame transfers.
+/// Returns true on success; false on invalid arguments, OOM, or TX queue exhaustion.
+/// A nonzero local node-ID is required.
+bool canard_v0_publish(canard_t* const self,
+ const canard_us_t deadline,
+ const uint_least8_t iface_bitmap,
+ const canard_prio_t priority,
+ const uint16_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+
+/// Enqueue a legacy v0 service request on all interfaces. A nonzero local node-ID and a nonzero destination node-ID
+/// are required; other TX semantics match canard_v0_publish().
+bool canard_v0_request(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t server_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+
+/// Enqueue a legacy v0 service response on all interfaces. A nonzero local node-ID and a nonzero destination node-ID
+/// are required; other TX semantics match canard_v0_publish().
+bool canard_v0_respond(canard_t* const self,
+ const canard_us_t deadline,
+ const canard_prio_t priority,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const uint_least8_t client_node_id,
+ const uint_least8_t transfer_id,
+ const canard_bytes_chain_t payload,
+ void* const user_context);
+
+/// Register a legacy v0 message subscription.
+/// Subscription updates are log-time; per-remote RX session state is allocated lazily on demand.
+bool canard_v0_subscribe(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint16_t data_type_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable);
+
+/// Register a legacy v0 request subscription.
+/// Subscription updates are log-time; per-remote RX session state is allocated lazily on demand.
+bool canard_v0_subscribe_request(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_us_t transfer_id_timeout,
+ const canard_subscription_vtable_t* const vtable);
+
+/// Register a legacy v0 response subscription.
+/// Response transfers necessarily have a zero transfer-ID timeout.
+/// Subscription updates are log-time; per-remote RX session state is allocated lazily on demand.
+bool canard_v0_subscribe_response(canard_t* const self,
+ canard_subscription_t* const subscription,
+ const uint_least8_t data_type_id,
+ const uint16_t crc_seed,
+ const size_t extent,
+ const canard_subscription_vtable_t* const vtable);
+
+/// Computes the CRC-16/CCITT-FALSE checksum of the data type signature in the little-endian byte order.
+/// This value is then used to seed the transfer CRC for UAVCAN v0 and DroneCAN transfers.
+uint16_t canard_v0_crc_seed_from_data_type_signature(const uint64_t data_type_signature);
#ifdef __cplusplus
}
diff --git a/tests/.clang-tidy b/tests/.clang-tidy
index 8d3c138b..012fe0db 100644
--- a/tests/.clang-tidy
+++ b/tests/.clang-tidy
@@ -1,6 +1,7 @@
---
# The tests are held to somewhat lower quality standards than production code.
# The tests are also written in somewhat non-idiomatic C++ because they are tightly related to the C codebase.
+InheritParentConfig: true
Checks: >-
boost-*,
bugprone-*,
@@ -31,16 +32,32 @@ Checks: >-
-cppcoreguidelines-pro-bounds-pointer-arithmetic,
-cppcoreguidelines-pro-bounds-constant-array-index,
-cppcoreguidelines-avoid-magic-numbers,
+ -cppcoreguidelines-avoid-const-or-ref-data-members,
-cppcoreguidelines-pro-type-union-access,
-cppcoreguidelines-pro-type-reinterpret-cast,
+ -boost-use-ranges,
+ -modernize-use-ranges,
-*-no-malloc,
-cert-msc30-c,
-cert-msc50-cpp,
-*-macro-to-enum,
+ -modernize-use-trailing-return-type,
+ -*-macro-usage,
+ -*-enum-size,
+ -*-use-using,
+ -cppcoreguidelines-owning-memory,
-misc-include-cleaner,
- -bugprone-chained-comparison,
-performance-avoid-endl,
- -*-use-ranges,
+ -cppcoreguidelines-avoid-do-while,
+ -*DeprecatedOrUnsafeBufferHandling,
+ -*-prefer-static-over-anonymous-namespace,
+ -*-pro-bounds-avoid-unchecked-container-access,
+ -*-array*decay,
+ -*-avoid-c-arrays,
+ -*-casting-through-void,
+ -*-named-parameter,
+ -misc-use-anonymous-namespace,
+ -misc-use-internal-linkage,
WarningsAsErrors: '*'
HeaderFilterRegex: '.*\.hpp'
FormatStyle: file
diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt
index 010230a2..e6af6994 100644
--- a/tests/CMakeLists.txt
+++ b/tests/CMakeLists.txt
@@ -4,125 +4,145 @@
# Contributors: https://github.com/OpenCyphal/libcanard/contributors.
cmake_minimum_required(VERSION 3.12)
+
+set(CMAKE_CXX_STANDARD 20)
+set(CMAKE_CXX_EXTENSIONS OFF)
+set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Woverloaded-virtual -Wnon-virtual-dtor -Wsign-promo")
+
project(canard_tests C CXX)
enable_testing()
set(CTEST_OUTPUT_ON_FAILURE ON)
-set(library_dir "${CMAKE_SOURCE_DIR}/../libcanard")
-
set(NO_STATIC_ANALYSIS OFF CACHE BOOL "disable canard static analysis")
-set(NO_CANARD_SANITIZER OFF CACHE BOOL "disable canard runtime sanitizers")
+set(ENABLE_COVERAGE OFF CACHE BOOL "enable code coverage measurement")
+set(library_dir "${CMAKE_SOURCE_DIR}/libcanard")
+set(unity_root "${CMAKE_SOURCE_DIR}/lib/unity")
-# Use -DNO_STATIC_ANALYSIS=1 to suppress static analysis.
-# If not suppressed, the tools used here shall be available, otherwise the build will fail.
+include_directories(SYSTEM ${CMAKE_SOURCE_DIR}/lib/cavl2)
+
+# Fail the build if poisoned identifiers are present.
+# Poison fixed-length 8-bit integer types to maximize portability across DSP cores that may not support them.
+set(POISON_REGEXP "\\b(int8_t|uint8_t)\\b")
if (NOT NO_STATIC_ANALYSIS)
- # clang-tidy (separate config files per directory)
- find_program(clang_tidy NAMES clang-tidy)
- if (NOT clang_tidy)
- message(FATAL_ERROR "Could not locate clang-tidy")
+ find_program(grep NAMES grep REQUIRED)
+ execute_process(
+ COMMAND "${grep}" -nE "${POISON_REGEXP}" "${library_dir}/canard.c" "${library_dir}/canard.h"
+ RESULT_VARIABLE grep_result
+ OUTPUT_VARIABLE grep_stdout
+ ERROR_VARIABLE grep_stderr
+ )
+ if (grep_result EQUAL 0)
+ message(FATAL_ERROR "Poisoned identifiers found:\n${grep_stdout}${grep_stderr}")
+ elseif (grep_result EQUAL 1)
+ message(STATUS "Poisoned identifiers not detected.")
+ else ()
+ message(FATAL_ERROR "Error occurred while searching for poisoned identifiers:\n${grep_stderr}")
endif ()
- message(STATUS "Using clang-tidy: ${clang_tidy}")
- set(CMAKE_C_CLANG_TIDY ${clang_tidy})
- set(CMAKE_CXX_CLANG_TIDY ${clang_tidy})
-endif()
-if(NOT NO_CANARD_SANITIZER)
- # libclang_rt.builtins-i386.a required by some sanitizers on x86-32 clang
- find_library(LLVM_RT_32 NAMES libclang_rt.builtins-i386.a PATHS /usr/lib/clang/)
- if(NOT LLVM_RT_32 MATCHES "NOTFOUND")
- message(STATUS "adding runtime for sanitizer ${LLVM_RT_32}")
- list(APPEND ADDITIONAL_LIBS_32 ${LLVM_RT_32})
- else()
- message(DEBUG "not adding clang runtime for sanitizer ${LLVM_RT_32}")
- endif()
- include(CheckCXXCompilerFlag)
- # Detect sanitizer compiler support.
- # Fail unit test only for no-sanitize-recover options. everything else warns to log only.
- set(UBSAN_FLAG "-fsanitize=undefined -fno-sanitize-recover=null,bounds,pointer-overflow,alignment,bool,builtin,float-cast-overflow,integer-divide-by-zero,nonnull-attribute,object-size,return,shift,unreachable,signed-integer-overflow,unsigned-integer-overflow,vptr")
- check_cxx_compiler_flag(${UBSAN_FLAG} UBSAN_SUPPORTED)
- check_cxx_compiler_flag(-fsanitize=address ASAN_SUPPORTED)
- if(UBSAN_SUPPORTED)
- message(STATUS "enabling undefined behavior sanitizer")
- list(APPEND SANITIZE_FLAG ${UBSAN_FLAG})
- endif()
- if(ASAN_SUPPORTED)
- message(STATUS "enabling address sanitizer")
- list(APPEND SANITIZE_FLAG -fsanitize=address)
- endif()
-endif ()
-
-# clang-format
-find_program(clang_format NAMES clang-format)
-if (NOT clang_format)
- message(STATUS "Could not locate clang-format")
-else ()
- file(GLOB format_files ${library_dir}/*.[ch] ${CMAKE_SOURCE_DIR}/*.[ch]pp)
- message(STATUS "Using clang-format: ${clang_format}; files: ${format_files}")
- add_custom_target(format COMMAND ${clang_format} -i -fallback-style=none -style=file --verbose ${format_files})
endif ()
-set(CMAKE_CXX_STANDARD 17)
-set(CXX_EXTENSIONS OFF)
-add_compile_options(
- -Wall -Wextra -Werror -pedantic -fstrict-aliasing -Wdouble-promotion -Wswitch-enum -Wfloat-equal -Wundef
- -Wconversion -Wtype-limits -Wsign-conversion -Wcast-align
-)
-set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Woverloaded-virtual -Wnon-virtual-dtor -Wsign-promo")
-
-include_directories(${library_dir})
-include_directories(SYSTEM catch)
-include_directories(SYSTEM ${CMAKE_SOURCE_DIR}/../lib/cavl2)
-add_definitions(-DCATCH_CONFIG_FAST_COMPILE=1 -DCATCH_CONFIG_ENABLE_ALL_STRINGMAKERS=1)
-
-set(common_sources ${CMAKE_SOURCE_DIR}/main.cpp ${library_dir}/canard.c)
-
function(gen_test name files compile_definitions compile_flags link_flags c_standard)
- add_executable(${name} ${common_sources} ${files})
+ # Unity. As an external dependency, it is excluded from static analysis.
+ add_library("${name}_unity" STATIC "${unity_root}/src/unity.c")
+ target_include_directories("${name}_unity" SYSTEM PUBLIC "${unity_root}/src/")
+ target_compile_definitions("${name}_unity" PUBLIC
+ UNITY_INCLUDE_DOUBLE=1 UNITY_OUTPUT_COLOR=1 UNITY_SUPPORT_64=1 UNITY_SHORTHAND_AS_RAW=1)
+ set_target_properties(
+ "${name}_unity"
+ PROPERTIES
+ COMPILE_FLAGS "${compile_flags} \
+ -Wno-sign-conversion -Wno-conversion -Wno-switch-enum -Wno-float-equal -Wno-double-promotion"
+ LINK_FLAGS "${link_flags}"
+ C_CLANG_TIDY ""
+ CXX_CLANG_TIDY ""
+ C_CPPCHECK ""
+ CXX_CPPCHECK ""
+ )
+ # Target executable
+ add_executable(${name} ${files})
+ target_include_directories(${name} PUBLIC ${library_dir})
target_compile_definitions(${name} PUBLIC ${compile_definitions})
- target_link_libraries(${name} pthread)
+ target_link_libraries(${name} "${name}_unity")
+ # Apply coverage flags if coverage is enabled.
+ if (ENABLE_COVERAGE)
+ target_compile_options(${name} PRIVATE --coverage -fprofile-arcs -ftest-coverage)
+ target_link_options(${name} PRIVATE --coverage -fprofile-arcs)
+ target_compile_definitions(${name} PRIVATE NDEBUG=1) # Remove assertion checks as they interfere with coverage.
+ endif ()
set_target_properties(
${name}
PROPERTIES
- COMPILE_FLAGS "${compile_flags}"
+ COMPILE_FLAGS "${compile_flags} -Wall -Wextra -Werror -pedantic -Wdouble-promotion -Wswitch-enum \
+ -Wfloat-equal -Wundef -Wconversion -Wtype-limits -Wsign-conversion -Wcast-align -Wmissing-declarations"
LINK_FLAGS "${link_flags}"
C_STANDARD "${c_standard}"
+ C_EXTENSIONS OFF
)
- add_test("run_${name}" "${name}" --rng-seed time)
+ add_test("run_${name}" "${name}")
endfunction()
-function(gen_test_matrix name files compile_definitions compile_flags link_flags)
- gen_test("${name}_x64_c99" "${files}" "${compile_definitions}" "${compile_flags} -m64" "-m64 ${link_flags}" "99")
- gen_test("${name}_x32_c99" "${files}" "${compile_definitions}" "${compile_flags} -m32" "-m32 ${link_flags}" "99")
- target_link_libraries("${name}_x32_c99" ${ADDITIONAL_LIBS_32})
- gen_test("${name}_x64_c11" "${files}" "${compile_definitions}" "${compile_flags} -m64" "-m64 ${link_flags}" "11")
- gen_test("${name}_x32_c11" "${files}" "${compile_definitions}" "${compile_flags} -m32" "-m32 ${link_flags}" "11")
- target_link_libraries("${name}_x32_c11" ${ADDITIONAL_LIBS_32})
- # Coverage is only available for GCC builds.
- if ((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND (CMAKE_BUILD_TYPE STREQUAL "Debug"))
- gen_test("${name}_cov"
- "${files}"
- "${compile_definitions}"
- "${compile_flags} -g -O0 --coverage"
- "--coverage"
- "11")
- endif ()
+function(gen_test_matrix name files)
+ gen_test("${name}_x64_c99" "${files}" "" "-m64" "-m64" "99")
+ gen_test("${name}_x32_c99" "${files}" "" "-m32" "-m32" "99")
+ gen_test("${name}_x64_c11" "${files}" "" "-m64" "-m64" "11")
+ gen_test("${name}_x32_c11" "${files}" "" "-m32" "-m32" "11")
endfunction()
-# Disable missing declaration warning to allow exposure of private definitions.
-gen_test_matrix(test_private
- "test_private_crc.cpp;test_private_rx.cpp;test_private_tx.cpp;"
- "-DCANARD_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/canard_config_private.h\""
- "-Wno-missing-declarations ${SANITIZE_FLAG}"
- "${SANITIZE_FLAG}")
-# test CRC with static table disabled
-gen_test_matrix(test_private_crc_table
- "test_private_crc.cpp;"
- "-DCANARD_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/canard_config_private.h\""
- "-DCANARD_CRC_TABLE=0"
- "-Wno-missing-declarations ${SANITIZE_FLAG}"
- "${SANITIZE_FLAG}")
-
-gen_test_matrix(test_public
- "test_public_tx.cpp;test_public_rx.cpp;test_public_roundtrip.cpp;test_self.cpp;test_public_filters.cpp"
- ""
- "-Wmissing-declarations ${SANITIZE_FLAG}"
- "${SANITIZE_FLAG}")
+function(gen_test_single name files) # When the full matrix is not needed, to keep pipelines fast.
+ gen_test("${name}" "${files}" "" "-m32" "-m32" "11")
+endfunction()
+
+# Add the test targets.
+# Intrusive tests directly #include to access the internals.
+gen_test_matrix(test_helpers "src/test_helpers.c")
+gen_test_matrix(test_intrusive_util "src/test_intrusive_util.c")
+gen_test_matrix(test_intrusive_tx "src/test_intrusive_tx.c")
+gen_test_matrix(test_intrusive_rx "src/test_intrusive_rx.c")
+gen_test_matrix(test_intrusive_rx_filter "src/test_intrusive_rx_filter.c")
+gen_test_matrix(test_intrusive_rx_admission "src/test_intrusive_rx_admission.c")
+gen_test_matrix(test_intrusive_rx_session "src/test_intrusive_rx_session.c")
+gen_test_matrix(test_intrusive_misc "src/test_intrusive_misc.c")
+# API tests.
+gen_test_single(test_api_tx "${library_dir}/canard.c;src/test_api_tx.cpp")
+gen_test_single(test_api_rx "${library_dir}/canard.c;src/test_api_rx.cpp")
+gen_test_single(test_api_roundtrip "${library_dir}/canard.c;src/test_api_roundtrip.cpp")
+gen_test_single(test_api_tx_queue "${library_dir}/canard.c;src/test_api_tx_queue.cpp")
+gen_test_single(test_api_rx_edge "${library_dir}/canard.c;src/test_api_rx_edge.cpp")
+gen_test_single(test_api_lifecycle "${library_dir}/canard.c;src/test_api_lifecycle.cpp")
+
+# Coverage targets. Usage:
+# cmake -DENABLE_COVERAGE=ON -DNO_STATIC_ANALYSIS=ON ..
+# make -j$(nproc) && ctest && make coverage
+# xdg-open coverage-html/index.html
+if (ENABLE_COVERAGE)
+ find_program(LCOV_PATH lcov REQUIRED)
+ find_program(GENHTML_PATH genhtml REQUIRED)
+
+ # Reset coverage counters.
+ add_custom_target(coverage-reset
+ COMMAND ${LCOV_PATH} --zerocounters --directory .
+ COMMAND ${LCOV_PATH} --capture --initial --directory . --output-file coverage-base.info
+ --rc lcov_branch_coverage=1
+ WORKING_DIRECTORY ${CMAKE_BINARY_DIR}
+ COMMENT "Resetting coverage counters"
+ )
+
+ # Generate coverage report.
+ add_custom_target(coverage
+ COMMAND ${LCOV_PATH} --capture --directory . --output-file coverage-total.info --rc lcov_branch_coverage=1
+ COMMAND ${LCOV_PATH} --extract coverage-total.info '*/libcanard/canard.c' --output-file coverage-canard.info
+ --rc lcov_branch_coverage=1
+
+ COMMAND ${CMAKE_COMMAND} -E echo ""
+ COMMAND ${CMAKE_COMMAND} -E echo "=== COVERAGE SUMMARY ==="
+ COMMAND ${LCOV_PATH} --list coverage-canard.info --rc lcov_branch_coverage=1
+ COMMAND ${CMAKE_COMMAND} -E echo "========================"
+ COMMAND ${CMAKE_COMMAND} -E echo ""
+
+ COMMAND ${GENHTML_PATH} coverage-canard.info --output-directory coverage-html --title "libcanard coverage"
+ --legend --demangle-cpp --branch-coverage
+ COMMAND ${CMAKE_COMMAND} -E echo "Coverage report: file://${CMAKE_BINARY_DIR}/coverage-html/index.html"
+
+ WORKING_DIRECTORY ${CMAKE_BINARY_DIR}
+ COMMENT "Generating coverage HTML report"
+ )
+endif ()
diff --git a/tests/README.md b/tests/README.md
new file mode 100644
index 00000000..6c1ab367
--- /dev/null
+++ b/tests/README.md
@@ -0,0 +1,15 @@
+# Test suite
+
+The test suite is composed of two parts: intrusive tests in C that directly `#include ` to reach and test the internals, and API-level tests in modern C++ that use the public API only and test the library as a black box. It is preferable to test all behaviors through the API only, and resort to intrusive tests *only when necessary* to reach internal logic that cannot be tested through the API.
+
+All tests are mandatory. The default build and `ctest` execution must run the complete suite; there are no optional/extended tiers that can be skipped.
+
+If you need a build directory, create one in the project root named with a `build` prefix; you can also use existing build directories if you prefer so. Do not create build directories anywhere else.
+
+Static analysis (Clang-Tidy, Cppcheck, etc) must be enabled during build on all targets except external dependencies (e.g., the test framework). In particular, Clang-Tidy and Cppcheck MUST BE ENABLED on the test suite and the Cy library itself at all times.
+
+When compiling, use multiple jobs to use all CPU cores.
+
+Run all tests in debug build to ensure that all assertion checks are enabled. Coverage builds should disable assertion checks to avoid reporting of uncovered fault branches in assert statements.
+
+Refer to the CI workflow files and `CMakeLists.txt` for the recommended practices on how to build and run the test suite.
diff --git a/tests/canard_config_private.h b/tests/canard_config_private.h
deleted file mode 100644
index c7db8dbe..00000000
--- a/tests/canard_config_private.h
+++ /dev/null
@@ -1,4 +0,0 @@
-// This libcanard config header is included from canard.c via CANARD_CONFIG_HEADER
-
-// Expose the internal definitions for testing.
-#define CANARD_PRIVATE
diff --git a/tests/catch/catch.hpp b/tests/catch/catch.hpp
deleted file mode 100644
index 9b309bdd..00000000
--- a/tests/catch/catch.hpp
+++ /dev/null
@@ -1,17976 +0,0 @@
-/*
- * Catch v2.13.10
- * Generated: 2022-10-16 11:01:23.452308
- * ----------------------------------------------------------
- * This file has been merged from multiple headers. Please don't edit it directly
- * Copyright (c) 2022 Two Blue Cubes Ltd. All rights reserved.
- *
- * Distributed under the Boost Software License, Version 1.0. (See accompanying
- * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
- */
-#ifndef TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-#define TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-// start catch.hpp
-
-
-#define CATCH_VERSION_MAJOR 2
-#define CATCH_VERSION_MINOR 13
-#define CATCH_VERSION_PATCH 10
-
-#ifdef __clang__
-# pragma clang system_header
-#elif defined __GNUC__
-# pragma GCC system_header
-#endif
-
-// start catch_suppress_warnings.h
-
-#ifdef __clang__
-# ifdef __ICC // icpc defines the __clang__ macro
-# pragma warning(push)
-# pragma warning(disable: 161 1682)
-# else // __ICC
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wpadded"
-# pragma clang diagnostic ignored "-Wswitch-enum"
-# pragma clang diagnostic ignored "-Wcovered-switch-default"
-# endif
-#elif defined __GNUC__
- // Because REQUIREs trigger GCC's -Wparentheses, and because still
- // supported version of g++ have only buggy support for _Pragmas,
- // Wparentheses have to be suppressed globally.
-# pragma GCC diagnostic ignored "-Wparentheses" // See #674 for details
-
-# pragma GCC diagnostic push
-# pragma GCC diagnostic ignored "-Wunused-variable"
-# pragma GCC diagnostic ignored "-Wpadded"
-#endif
-// end catch_suppress_warnings.h
-#if defined(CATCH_CONFIG_MAIN) || defined(CATCH_CONFIG_RUNNER)
-# define CATCH_IMPL
-# define CATCH_CONFIG_ALL_PARTS
-#endif
-
-// In the impl file, we want to have access to all parts of the headers
-// Can also be used to sanely support PCHs
-#if defined(CATCH_CONFIG_ALL_PARTS)
-# define CATCH_CONFIG_EXTERNAL_INTERFACES
-# if defined(CATCH_CONFIG_DISABLE_MATCHERS)
-# undef CATCH_CONFIG_DISABLE_MATCHERS
-# endif
-# if !defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER)
-# define CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER
-# endif
-#endif
-
-#if !defined(CATCH_CONFIG_IMPL_ONLY)
-// start catch_platform.h
-
-// See e.g.:
-// https://opensource.apple.com/source/CarbonHeaders/CarbonHeaders-18.1/TargetConditionals.h.auto.html
-#ifdef __APPLE__
-# include
-# if (defined(TARGET_OS_OSX) && TARGET_OS_OSX == 1) || \
- (defined(TARGET_OS_MAC) && TARGET_OS_MAC == 1)
-# define CATCH_PLATFORM_MAC
-# elif (defined(TARGET_OS_IPHONE) && TARGET_OS_IPHONE == 1)
-# define CATCH_PLATFORM_IPHONE
-# endif
-
-#elif defined(linux) || defined(__linux) || defined(__linux__)
-# define CATCH_PLATFORM_LINUX
-
-#elif defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER) || defined(__MINGW32__)
-# define CATCH_PLATFORM_WINDOWS
-#endif
-
-// end catch_platform.h
-
-#ifdef CATCH_IMPL
-# ifndef CLARA_CONFIG_MAIN
-# define CLARA_CONFIG_MAIN_NOT_DEFINED
-# define CLARA_CONFIG_MAIN
-# endif
-#endif
-
-// start catch_user_interfaces.h
-
-namespace Catch {
- unsigned int rngSeed();
-}
-
-// end catch_user_interfaces.h
-// start catch_tag_alias_autoregistrar.h
-
-// start catch_common.h
-
-// start catch_compiler_capabilities.h
-
-// Detect a number of compiler features - by compiler
-// The following features are defined:
-//
-// CATCH_CONFIG_COUNTER : is the __COUNTER__ macro supported?
-// CATCH_CONFIG_WINDOWS_SEH : is Windows SEH supported?
-// CATCH_CONFIG_POSIX_SIGNALS : are POSIX signals supported?
-// CATCH_CONFIG_DISABLE_EXCEPTIONS : Are exceptions enabled?
-// ****************
-// Note to maintainers: if new toggles are added please document them
-// in configuration.md, too
-// ****************
-
-// In general each macro has a _NO_ form
-// (e.g. CATCH_CONFIG_NO_POSIX_SIGNALS) which disables the feature.
-// Many features, at point of detection, define an _INTERNAL_ macro, so they
-// can be combined, en-mass, with the _NO_ forms later.
-
-#ifdef __cplusplus
-
-# if (__cplusplus >= 201402L) || (defined(_MSVC_LANG) && _MSVC_LANG >= 201402L)
-# define CATCH_CPP14_OR_GREATER
-# endif
-
-# if (__cplusplus >= 201703L) || (defined(_MSVC_LANG) && _MSVC_LANG >= 201703L)
-# define CATCH_CPP17_OR_GREATER
-# endif
-
-#endif
-
-// Only GCC compiler should be used in this block, so other compilers trying to
-// mask themselves as GCC should be ignored.
-#if defined(__GNUC__) && !defined(__clang__) && !defined(__ICC) && !defined(__CUDACC__) && !defined(__LCC__)
-# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION _Pragma( "GCC diagnostic push" )
-# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION _Pragma( "GCC diagnostic pop" )
-
-# define CATCH_INTERNAL_IGNORE_BUT_WARN(...) (void)__builtin_constant_p(__VA_ARGS__)
-
-#endif
-
-#if defined(__clang__)
-
-# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION _Pragma( "clang diagnostic push" )
-# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION _Pragma( "clang diagnostic pop" )
-
-// As of this writing, IBM XL's implementation of __builtin_constant_p has a bug
-// which results in calls to destructors being emitted for each temporary,
-// without a matching initialization. In practice, this can result in something
-// like `std::string::~string` being called on an uninitialized value.
-//
-// For example, this code will likely segfault under IBM XL:
-// ```
-// REQUIRE(std::string("12") + "34" == "1234")
-// ```
-//
-// Therefore, `CATCH_INTERNAL_IGNORE_BUT_WARN` is not implemented.
-# if !defined(__ibmxl__) && !defined(__CUDACC__)
-# define CATCH_INTERNAL_IGNORE_BUT_WARN(...) (void)__builtin_constant_p(__VA_ARGS__) /* NOLINT(cppcoreguidelines-pro-type-vararg, hicpp-vararg) */
-# endif
-
-# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- _Pragma( "clang diagnostic ignored \"-Wexit-time-destructors\"" ) \
- _Pragma( "clang diagnostic ignored \"-Wglobal-constructors\"")
-
-# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \
- _Pragma( "clang diagnostic ignored \"-Wparentheses\"" )
-
-# define CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS \
- _Pragma( "clang diagnostic ignored \"-Wunused-variable\"" )
-
-# define CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS \
- _Pragma( "clang diagnostic ignored \"-Wgnu-zero-variadic-macro-arguments\"" )
-
-# define CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- _Pragma( "clang diagnostic ignored \"-Wunused-template\"" )
-
-#endif // __clang__
-
-////////////////////////////////////////////////////////////////////////////////
-// Assume that non-Windows platforms support posix signals by default
-#if !defined(CATCH_PLATFORM_WINDOWS)
- #define CATCH_INTERNAL_CONFIG_POSIX_SIGNALS
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// We know some environments not to support full POSIX signals
-#if defined(__CYGWIN__) || defined(__QNX__) || defined(__EMSCRIPTEN__) || defined(__DJGPP__)
- #define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS
-#endif
-
-#ifdef __OS400__
-# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS
-# define CATCH_CONFIG_COLOUR_NONE
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// Android somehow still does not support std::to_string
-#if defined(__ANDROID__)
-# define CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING
-# define CATCH_INTERNAL_CONFIG_ANDROID_LOGWRITE
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// Not all Windows environments support SEH properly
-#if defined(__MINGW32__)
-# define CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// PS4
-#if defined(__ORBIS__)
-# define CATCH_INTERNAL_CONFIG_NO_NEW_CAPTURE
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// Cygwin
-#ifdef __CYGWIN__
-
-// Required for some versions of Cygwin to declare gettimeofday
-// see: http://stackoverflow.com/questions/36901803/gettimeofday-not-declared-in-this-scope-cygwin
-# define _BSD_SOURCE
-// some versions of cygwin (most) do not support std::to_string. Use the libstd check.
-// https://gcc.gnu.org/onlinedocs/gcc-4.8.2/libstdc++/api/a01053_source.html line 2812-2813
-# if !((__cplusplus >= 201103L) && defined(_GLIBCXX_USE_C99) \
- && !defined(_GLIBCXX_HAVE_BROKEN_VSWPRINTF))
-
-# define CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING
-
-# endif
-#endif // __CYGWIN__
-
-////////////////////////////////////////////////////////////////////////////////
-// Visual C++
-#if defined(_MSC_VER)
-
-// Universal Windows platform does not support SEH
-// Or console colours (or console at all...)
-# if defined(WINAPI_FAMILY) && (WINAPI_FAMILY == WINAPI_FAMILY_APP)
-# define CATCH_CONFIG_COLOUR_NONE
-# else
-# define CATCH_INTERNAL_CONFIG_WINDOWS_SEH
-# endif
-
-# if !defined(__clang__) // Handle Clang masquerading for msvc
-
-// MSVC traditional preprocessor needs some workaround for __VA_ARGS__
-// _MSVC_TRADITIONAL == 0 means new conformant preprocessor
-// _MSVC_TRADITIONAL == 1 means old traditional non-conformant preprocessor
-# if !defined(_MSVC_TRADITIONAL) || (defined(_MSVC_TRADITIONAL) && _MSVC_TRADITIONAL)
-# define CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
-# endif // MSVC_TRADITIONAL
-
-// Only do this if we're not using clang on Windows, which uses `diagnostic push` & `diagnostic pop`
-# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION __pragma( warning(push) )
-# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION __pragma( warning(pop) )
-# endif // __clang__
-
-#endif // _MSC_VER
-
-#if defined(_REENTRANT) || defined(_MSC_VER)
-// Enable async processing, as -pthread is specified or no additional linking is required
-# define CATCH_INTERNAL_CONFIG_USE_ASYNC
-#endif // _MSC_VER
-
-////////////////////////////////////////////////////////////////////////////////
-// Check if we are compiled with -fno-exceptions or equivalent
-#if defined(__EXCEPTIONS) || defined(__cpp_exceptions) || defined(_CPPUNWIND)
-# define CATCH_INTERNAL_CONFIG_EXCEPTIONS_ENABLED
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// DJGPP
-#ifdef __DJGPP__
-# define CATCH_INTERNAL_CONFIG_NO_WCHAR
-#endif // __DJGPP__
-
-////////////////////////////////////////////////////////////////////////////////
-// Embarcadero C++Build
-#if defined(__BORLANDC__)
- #define CATCH_INTERNAL_CONFIG_POLYFILL_ISNAN
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-
-// Use of __COUNTER__ is suppressed during code analysis in
-// CLion/AppCode 2017.2.x and former, because __COUNTER__ is not properly
-// handled by it.
-// Otherwise all supported compilers support COUNTER macro,
-// but user still might want to turn it off
-#if ( !defined(__JETBRAINS_IDE__) || __JETBRAINS_IDE__ >= 20170300L )
- #define CATCH_INTERNAL_CONFIG_COUNTER
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-
-// RTX is a special version of Windows that is real time.
-// This means that it is detected as Windows, but does not provide
-// the same set of capabilities as real Windows does.
-#if defined(UNDER_RTSS) || defined(RTX64_BUILD)
- #define CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH
- #define CATCH_INTERNAL_CONFIG_NO_ASYNC
- #define CATCH_CONFIG_COLOUR_NONE
-#endif
-
-#if !defined(_GLIBCXX_USE_C99_MATH_TR1)
-#define CATCH_INTERNAL_CONFIG_GLOBAL_NEXTAFTER
-#endif
-
-// Various stdlib support checks that require __has_include
-#if defined(__has_include)
- // Check if string_view is available and usable
- #if __has_include() && defined(CATCH_CPP17_OR_GREATER)
- # define CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW
- #endif
-
- // Check if optional is available and usable
- # if __has_include() && defined(CATCH_CPP17_OR_GREATER)
- # define CATCH_INTERNAL_CONFIG_CPP17_OPTIONAL
- # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER)
-
- // Check if byte is available and usable
- # if __has_include() && defined(CATCH_CPP17_OR_GREATER)
- # include
- # if defined(__cpp_lib_byte) && (__cpp_lib_byte > 0)
- # define CATCH_INTERNAL_CONFIG_CPP17_BYTE
- # endif
- # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER)
-
- // Check if variant is available and usable
- # if __has_include() && defined(CATCH_CPP17_OR_GREATER)
- # if defined(__clang__) && (__clang_major__ < 8)
- // work around clang bug with libstdc++ https://bugs.llvm.org/show_bug.cgi?id=31852
- // fix should be in clang 8, workaround in libstdc++ 8.2
- # include
- # if defined(__GLIBCXX__) && defined(_GLIBCXX_RELEASE) && (_GLIBCXX_RELEASE < 9)
- # define CATCH_CONFIG_NO_CPP17_VARIANT
- # else
- # define CATCH_INTERNAL_CONFIG_CPP17_VARIANT
- # endif // defined(__GLIBCXX__) && defined(_GLIBCXX_RELEASE) && (_GLIBCXX_RELEASE < 9)
- # else
- # define CATCH_INTERNAL_CONFIG_CPP17_VARIANT
- # endif // defined(__clang__) && (__clang_major__ < 8)
- # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER)
-#endif // defined(__has_include)
-
-#if defined(CATCH_INTERNAL_CONFIG_COUNTER) && !defined(CATCH_CONFIG_NO_COUNTER) && !defined(CATCH_CONFIG_COUNTER)
-# define CATCH_CONFIG_COUNTER
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_WINDOWS_SEH) && !defined(CATCH_CONFIG_NO_WINDOWS_SEH) && !defined(CATCH_CONFIG_WINDOWS_SEH) && !defined(CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH)
-# define CATCH_CONFIG_WINDOWS_SEH
-#endif
-// This is set by default, because we assume that unix compilers are posix-signal-compatible by default.
-#if defined(CATCH_INTERNAL_CONFIG_POSIX_SIGNALS) && !defined(CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_POSIX_SIGNALS)
-# define CATCH_CONFIG_POSIX_SIGNALS
-#endif
-// This is set by default, because we assume that compilers with no wchar_t support are just rare exceptions.
-#if !defined(CATCH_INTERNAL_CONFIG_NO_WCHAR) && !defined(CATCH_CONFIG_NO_WCHAR) && !defined(CATCH_CONFIG_WCHAR)
-# define CATCH_CONFIG_WCHAR
-#endif
-
-#if !defined(CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING) && !defined(CATCH_CONFIG_NO_CPP11_TO_STRING) && !defined(CATCH_CONFIG_CPP11_TO_STRING)
-# define CATCH_CONFIG_CPP11_TO_STRING
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_CPP17_OPTIONAL) && !defined(CATCH_CONFIG_NO_CPP17_OPTIONAL) && !defined(CATCH_CONFIG_CPP17_OPTIONAL)
-# define CATCH_CONFIG_CPP17_OPTIONAL
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_NO_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_CPP17_STRING_VIEW)
-# define CATCH_CONFIG_CPP17_STRING_VIEW
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_CPP17_VARIANT) && !defined(CATCH_CONFIG_NO_CPP17_VARIANT) && !defined(CATCH_CONFIG_CPP17_VARIANT)
-# define CATCH_CONFIG_CPP17_VARIANT
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_CPP17_BYTE) && !defined(CATCH_CONFIG_NO_CPP17_BYTE) && !defined(CATCH_CONFIG_CPP17_BYTE)
-# define CATCH_CONFIG_CPP17_BYTE
-#endif
-
-#if defined(CATCH_CONFIG_EXPERIMENTAL_REDIRECT)
-# define CATCH_INTERNAL_CONFIG_NEW_CAPTURE
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_NEW_CAPTURE) && !defined(CATCH_INTERNAL_CONFIG_NO_NEW_CAPTURE) && !defined(CATCH_CONFIG_NO_NEW_CAPTURE) && !defined(CATCH_CONFIG_NEW_CAPTURE)
-# define CATCH_CONFIG_NEW_CAPTURE
-#endif
-
-#if !defined(CATCH_INTERNAL_CONFIG_EXCEPTIONS_ENABLED) && !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS)
-# define CATCH_CONFIG_DISABLE_EXCEPTIONS
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_POLYFILL_ISNAN) && !defined(CATCH_CONFIG_NO_POLYFILL_ISNAN) && !defined(CATCH_CONFIG_POLYFILL_ISNAN)
-# define CATCH_CONFIG_POLYFILL_ISNAN
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_USE_ASYNC) && !defined(CATCH_INTERNAL_CONFIG_NO_ASYNC) && !defined(CATCH_CONFIG_NO_USE_ASYNC) && !defined(CATCH_CONFIG_USE_ASYNC)
-# define CATCH_CONFIG_USE_ASYNC
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_ANDROID_LOGWRITE) && !defined(CATCH_CONFIG_NO_ANDROID_LOGWRITE) && !defined(CATCH_CONFIG_ANDROID_LOGWRITE)
-# define CATCH_CONFIG_ANDROID_LOGWRITE
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_GLOBAL_NEXTAFTER) && !defined(CATCH_CONFIG_NO_GLOBAL_NEXTAFTER) && !defined(CATCH_CONFIG_GLOBAL_NEXTAFTER)
-# define CATCH_CONFIG_GLOBAL_NEXTAFTER
-#endif
-
-// Even if we do not think the compiler has that warning, we still have
-// to provide a macro that can be used by the code.
-#if !defined(CATCH_INTERNAL_START_WARNINGS_SUPPRESSION)
-# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION
-#endif
-#if !defined(CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION)
-# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION
-#endif
-#if !defined(CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS
-#endif
-#if !defined(CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS
-#endif
-#if !defined(CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS
-#endif
-#if !defined(CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS
-#endif
-
-// The goal of this macro is to avoid evaluation of the arguments, but
-// still have the compiler warn on problems inside...
-#if !defined(CATCH_INTERNAL_IGNORE_BUT_WARN)
-# define CATCH_INTERNAL_IGNORE_BUT_WARN(...)
-#endif
-
-#if defined(__APPLE__) && defined(__apple_build_version__) && (__clang_major__ < 10)
-# undef CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS
-#elif defined(__clang__) && (__clang_major__ < 5)
-# undef CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS
-#endif
-
-#if !defined(CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS
-#endif
-
-#if defined(CATCH_CONFIG_DISABLE_EXCEPTIONS)
-#define CATCH_TRY if ((true))
-#define CATCH_CATCH_ALL if ((false))
-#define CATCH_CATCH_ANON(type) if ((false))
-#else
-#define CATCH_TRY try
-#define CATCH_CATCH_ALL catch (...)
-#define CATCH_CATCH_ANON(type) catch (type)
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR) && !defined(CATCH_CONFIG_NO_TRADITIONAL_MSVC_PREPROCESSOR) && !defined(CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR)
-#define CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
-#endif
-
-// end catch_compiler_capabilities.h
-#define INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) name##line
-#define INTERNAL_CATCH_UNIQUE_NAME_LINE( name, line ) INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line )
-#ifdef CATCH_CONFIG_COUNTER
-# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __COUNTER__ )
-#else
-# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __LINE__ )
-#endif
-
-#include
-#include
-#include
-
-// We need a dummy global operator<< so we can bring it into Catch namespace later
-struct Catch_global_namespace_dummy {};
-std::ostream& operator<<(std::ostream&, Catch_global_namespace_dummy);
-
-namespace Catch {
-
- struct CaseSensitive { enum Choice {
- Yes,
- No
- }; };
-
- class NonCopyable {
- NonCopyable( NonCopyable const& ) = delete;
- NonCopyable( NonCopyable && ) = delete;
- NonCopyable& operator = ( NonCopyable const& ) = delete;
- NonCopyable& operator = ( NonCopyable && ) = delete;
-
- protected:
- NonCopyable();
- virtual ~NonCopyable();
- };
-
- struct SourceLineInfo {
-
- SourceLineInfo() = delete;
- SourceLineInfo( char const* _file, std::size_t _line ) noexcept
- : file( _file ),
- line( _line )
- {}
-
- SourceLineInfo( SourceLineInfo const& other ) = default;
- SourceLineInfo& operator = ( SourceLineInfo const& ) = default;
- SourceLineInfo( SourceLineInfo&& ) noexcept = default;
- SourceLineInfo& operator = ( SourceLineInfo&& ) noexcept = default;
-
- bool empty() const noexcept { return file[0] == '\0'; }
- bool operator == ( SourceLineInfo const& other ) const noexcept;
- bool operator < ( SourceLineInfo const& other ) const noexcept;
-
- char const* file;
- std::size_t line;
- };
-
- std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info );
-
- // Bring in operator<< from global namespace into Catch namespace
- // This is necessary because the overload of operator<< above makes
- // lookup stop at namespace Catch
- using ::operator<<;
-
- // Use this in variadic streaming macros to allow
- // >> +StreamEndStop
- // as well as
- // >> stuff +StreamEndStop
- struct StreamEndStop {
- std::string operator+() const;
- };
- template
- T const& operator + ( T const& value, StreamEndStop ) {
- return value;
- }
-}
-
-#define CATCH_INTERNAL_LINEINFO \
- ::Catch::SourceLineInfo( __FILE__, static_cast( __LINE__ ) )
-
-// end catch_common.h
-namespace Catch {
-
- struct RegistrarForTagAliases {
- RegistrarForTagAliases( char const* alias, char const* tag, SourceLineInfo const& lineInfo );
- };
-
-} // end namespace Catch
-
-#define CATCH_REGISTER_TAG_ALIAS( alias, spec ) \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::RegistrarForTagAliases INTERNAL_CATCH_UNIQUE_NAME( AutoRegisterTagAlias )( alias, spec, CATCH_INTERNAL_LINEINFO ); } \
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION
-
-// end catch_tag_alias_autoregistrar.h
-// start catch_test_registry.h
-
-// start catch_interfaces_testcase.h
-
-#include
-
-namespace Catch {
-
- class TestSpec;
-
- struct ITestInvoker {
- virtual void invoke () const = 0;
- virtual ~ITestInvoker();
- };
-
- class TestCase;
- struct IConfig;
-
- struct ITestCaseRegistry {
- virtual ~ITestCaseRegistry();
- virtual std::vector const& getAllTests() const = 0;
- virtual std::vector const& getAllTestsSorted( IConfig const& config ) const = 0;
- };
-
- bool isThrowSafe( TestCase const& testCase, IConfig const& config );
- bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config );
- std::vector filterTests( std::vector const& testCases, TestSpec const& testSpec, IConfig const& config );
- std::vector const& getAllTestCasesSorted( IConfig const& config );
-
-}
-
-// end catch_interfaces_testcase.h
-// start catch_stringref.h
-
-#include
-#include
-#include
-#include
-
-namespace Catch {
-
- /// A non-owning string class (similar to the forthcoming std::string_view)
- /// Note that, because a StringRef may be a substring of another string,
- /// it may not be null terminated.
- class StringRef {
- public:
- using size_type = std::size_t;
- using const_iterator = const char*;
-
- private:
- static constexpr char const* const s_empty = "";
-
- char const* m_start = s_empty;
- size_type m_size = 0;
-
- public: // construction
- constexpr StringRef() noexcept = default;
-
- StringRef( char const* rawChars ) noexcept;
-
- constexpr StringRef( char const* rawChars, size_type size ) noexcept
- : m_start( rawChars ),
- m_size( size )
- {}
-
- StringRef( std::string const& stdString ) noexcept
- : m_start( stdString.c_str() ),
- m_size( stdString.size() )
- {}
-
- explicit operator std::string() const {
- return std::string(m_start, m_size);
- }
-
- public: // operators
- auto operator == ( StringRef const& other ) const noexcept -> bool;
- auto operator != (StringRef const& other) const noexcept -> bool {
- return !(*this == other);
- }
-
- auto operator[] ( size_type index ) const noexcept -> char {
- assert(index < m_size);
- return m_start[index];
- }
-
- public: // named queries
- constexpr auto empty() const noexcept -> bool {
- return m_size == 0;
- }
- constexpr auto size() const noexcept -> size_type {
- return m_size;
- }
-
- // Returns the current start pointer. If the StringRef is not
- // null-terminated, throws std::domain_exception
- auto c_str() const -> char const*;
-
- public: // substrings and searches
- // Returns a substring of [start, start + length).
- // If start + length > size(), then the substring is [start, size()).
- // If start > size(), then the substring is empty.
- auto substr( size_type start, size_type length ) const noexcept -> StringRef;
-
- // Returns the current start pointer. May not be null-terminated.
- auto data() const noexcept -> char const*;
-
- constexpr auto isNullTerminated() const noexcept -> bool {
- return m_start[m_size] == '\0';
- }
-
- public: // iterators
- constexpr const_iterator begin() const { return m_start; }
- constexpr const_iterator end() const { return m_start + m_size; }
- };
-
- auto operator += ( std::string& lhs, StringRef const& sr ) -> std::string&;
- auto operator << ( std::ostream& os, StringRef const& sr ) -> std::ostream&;
-
- constexpr auto operator "" _sr( char const* rawChars, std::size_t size ) noexcept -> StringRef {
- return StringRef( rawChars, size );
- }
-} // namespace Catch
-
-constexpr auto operator "" _catch_sr( char const* rawChars, std::size_t size ) noexcept -> Catch::StringRef {
- return Catch::StringRef( rawChars, size );
-}
-
-// end catch_stringref.h
-// start catch_preprocessor.hpp
-
-
-#define CATCH_RECURSION_LEVEL0(...) __VA_ARGS__
-#define CATCH_RECURSION_LEVEL1(...) CATCH_RECURSION_LEVEL0(CATCH_RECURSION_LEVEL0(CATCH_RECURSION_LEVEL0(__VA_ARGS__)))
-#define CATCH_RECURSION_LEVEL2(...) CATCH_RECURSION_LEVEL1(CATCH_RECURSION_LEVEL1(CATCH_RECURSION_LEVEL1(__VA_ARGS__)))
-#define CATCH_RECURSION_LEVEL3(...) CATCH_RECURSION_LEVEL2(CATCH_RECURSION_LEVEL2(CATCH_RECURSION_LEVEL2(__VA_ARGS__)))
-#define CATCH_RECURSION_LEVEL4(...) CATCH_RECURSION_LEVEL3(CATCH_RECURSION_LEVEL3(CATCH_RECURSION_LEVEL3(__VA_ARGS__)))
-#define CATCH_RECURSION_LEVEL5(...) CATCH_RECURSION_LEVEL4(CATCH_RECURSION_LEVEL4(CATCH_RECURSION_LEVEL4(__VA_ARGS__)))
-
-#ifdef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
-#define INTERNAL_CATCH_EXPAND_VARGS(...) __VA_ARGS__
-// MSVC needs more evaluations
-#define CATCH_RECURSION_LEVEL6(...) CATCH_RECURSION_LEVEL5(CATCH_RECURSION_LEVEL5(CATCH_RECURSION_LEVEL5(__VA_ARGS__)))
-#define CATCH_RECURSE(...) CATCH_RECURSION_LEVEL6(CATCH_RECURSION_LEVEL6(__VA_ARGS__))
-#else
-#define CATCH_RECURSE(...) CATCH_RECURSION_LEVEL5(__VA_ARGS__)
-#endif
-
-#define CATCH_REC_END(...)
-#define CATCH_REC_OUT
-
-#define CATCH_EMPTY()
-#define CATCH_DEFER(id) id CATCH_EMPTY()
-
-#define CATCH_REC_GET_END2() 0, CATCH_REC_END
-#define CATCH_REC_GET_END1(...) CATCH_REC_GET_END2
-#define CATCH_REC_GET_END(...) CATCH_REC_GET_END1
-#define CATCH_REC_NEXT0(test, next, ...) next CATCH_REC_OUT
-#define CATCH_REC_NEXT1(test, next) CATCH_DEFER ( CATCH_REC_NEXT0 ) ( test, next, 0)
-#define CATCH_REC_NEXT(test, next) CATCH_REC_NEXT1(CATCH_REC_GET_END test, next)
-
-#define CATCH_REC_LIST0(f, x, peek, ...) , f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1) ) ( f, peek, __VA_ARGS__ )
-#define CATCH_REC_LIST1(f, x, peek, ...) , f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST0) ) ( f, peek, __VA_ARGS__ )
-#define CATCH_REC_LIST2(f, x, peek, ...) f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1) ) ( f, peek, __VA_ARGS__ )
-
-#define CATCH_REC_LIST0_UD(f, userdata, x, peek, ...) , f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1_UD) ) ( f, userdata, peek, __VA_ARGS__ )
-#define CATCH_REC_LIST1_UD(f, userdata, x, peek, ...) , f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST0_UD) ) ( f, userdata, peek, __VA_ARGS__ )
-#define CATCH_REC_LIST2_UD(f, userdata, x, peek, ...) f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1_UD) ) ( f, userdata, peek, __VA_ARGS__ )
-
-// Applies the function macro `f` to each of the remaining parameters, inserts commas between the results,
-// and passes userdata as the first parameter to each invocation,
-// e.g. CATCH_REC_LIST_UD(f, x, a, b, c) evaluates to f(x, a), f(x, b), f(x, c)
-#define CATCH_REC_LIST_UD(f, userdata, ...) CATCH_RECURSE(CATCH_REC_LIST2_UD(f, userdata, __VA_ARGS__, ()()(), ()()(), ()()(), 0))
-
-#define CATCH_REC_LIST(f, ...) CATCH_RECURSE(CATCH_REC_LIST2(f, __VA_ARGS__, ()()(), ()()(), ()()(), 0))
-
-#define INTERNAL_CATCH_EXPAND1(param) INTERNAL_CATCH_EXPAND2(param)
-#define INTERNAL_CATCH_EXPAND2(...) INTERNAL_CATCH_NO## __VA_ARGS__
-#define INTERNAL_CATCH_DEF(...) INTERNAL_CATCH_DEF __VA_ARGS__
-#define INTERNAL_CATCH_NOINTERNAL_CATCH_DEF
-#define INTERNAL_CATCH_STRINGIZE(...) INTERNAL_CATCH_STRINGIZE2(__VA_ARGS__)
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
-#define INTERNAL_CATCH_STRINGIZE2(...) #__VA_ARGS__
-#define INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS(param) INTERNAL_CATCH_STRINGIZE(INTERNAL_CATCH_REMOVE_PARENS(param))
-#else
-// MSVC is adding extra space and needs another indirection to expand INTERNAL_CATCH_NOINTERNAL_CATCH_DEF
-#define INTERNAL_CATCH_STRINGIZE2(...) INTERNAL_CATCH_STRINGIZE3(__VA_ARGS__)
-#define INTERNAL_CATCH_STRINGIZE3(...) #__VA_ARGS__
-#define INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS(param) (INTERNAL_CATCH_STRINGIZE(INTERNAL_CATCH_REMOVE_PARENS(param)) + 1)
-#endif
-
-#define INTERNAL_CATCH_MAKE_NAMESPACE2(...) ns_##__VA_ARGS__
-#define INTERNAL_CATCH_MAKE_NAMESPACE(name) INTERNAL_CATCH_MAKE_NAMESPACE2(name)
-
-#define INTERNAL_CATCH_REMOVE_PARENS(...) INTERNAL_CATCH_EXPAND1(INTERNAL_CATCH_DEF __VA_ARGS__)
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
-#define INTERNAL_CATCH_MAKE_TYPE_LIST2(...) decltype(get_wrapper())
-#define INTERNAL_CATCH_MAKE_TYPE_LIST(...) INTERNAL_CATCH_MAKE_TYPE_LIST2(INTERNAL_CATCH_REMOVE_PARENS(__VA_ARGS__))
-#else
-#define INTERNAL_CATCH_MAKE_TYPE_LIST2(...) INTERNAL_CATCH_EXPAND_VARGS(decltype(get_wrapper()))
-#define INTERNAL_CATCH_MAKE_TYPE_LIST(...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_MAKE_TYPE_LIST2(INTERNAL_CATCH_REMOVE_PARENS(__VA_ARGS__)))
-#endif
-
-#define INTERNAL_CATCH_MAKE_TYPE_LISTS_FROM_TYPES(...)\
- CATCH_REC_LIST(INTERNAL_CATCH_MAKE_TYPE_LIST,__VA_ARGS__)
-
-#define INTERNAL_CATCH_REMOVE_PARENS_1_ARG(_0) INTERNAL_CATCH_REMOVE_PARENS(_0)
-#define INTERNAL_CATCH_REMOVE_PARENS_2_ARG(_0, _1) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_1_ARG(_1)
-#define INTERNAL_CATCH_REMOVE_PARENS_3_ARG(_0, _1, _2) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_2_ARG(_1, _2)
-#define INTERNAL_CATCH_REMOVE_PARENS_4_ARG(_0, _1, _2, _3) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_3_ARG(_1, _2, _3)
-#define INTERNAL_CATCH_REMOVE_PARENS_5_ARG(_0, _1, _2, _3, _4) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_4_ARG(_1, _2, _3, _4)
-#define INTERNAL_CATCH_REMOVE_PARENS_6_ARG(_0, _1, _2, _3, _4, _5) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_5_ARG(_1, _2, _3, _4, _5)
-#define INTERNAL_CATCH_REMOVE_PARENS_7_ARG(_0, _1, _2, _3, _4, _5, _6) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_6_ARG(_1, _2, _3, _4, _5, _6)
-#define INTERNAL_CATCH_REMOVE_PARENS_8_ARG(_0, _1, _2, _3, _4, _5, _6, _7) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_7_ARG(_1, _2, _3, _4, _5, _6, _7)
-#define INTERNAL_CATCH_REMOVE_PARENS_9_ARG(_0, _1, _2, _3, _4, _5, _6, _7, _8) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_8_ARG(_1, _2, _3, _4, _5, _6, _7, _8)
-#define INTERNAL_CATCH_REMOVE_PARENS_10_ARG(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_9_ARG(_1, _2, _3, _4, _5, _6, _7, _8, _9)
-#define INTERNAL_CATCH_REMOVE_PARENS_11_ARG(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_10_ARG(_1, _2, _3, _4, _5, _6, _7, _8, _9, _10)
-
-#define INTERNAL_CATCH_VA_NARGS_IMPL(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, N, ...) N
-
-#define INTERNAL_CATCH_TYPE_GEN\
- template struct TypeList {};\
- template\
- constexpr auto get_wrapper() noexcept -> TypeList { return {}; }\
- template class...> struct TemplateTypeList{};\
- template class...Cs>\
- constexpr auto get_wrapper() noexcept -> TemplateTypeList { return {}; }\
- template\
- struct append;\
- template\
- struct rewrap;\
- template class, typename...>\
- struct create;\
- template class, typename>\
- struct convert;\
- \
- template \
- struct append { using type = T; };\
- template< template class L1, typename...E1, template class L2, typename...E2, typename...Rest>\
- struct append, L2, Rest...> { using type = typename append, Rest...>::type; };\
- template< template class L1, typename...E1, typename...Rest>\
- struct append, TypeList, Rest...> { using type = L1; };\
- \
- template< template class Container, template class List, typename...elems>\
- struct rewrap, List> { using type = TypeList>; };\
- template< template class Container, template class List, class...Elems, typename...Elements>\
- struct rewrap, List, Elements...> { using type = typename append>, typename rewrap, Elements...>::type>::type; };\
- \
- template class Final, template< typename...> class...Containers, typename...Types>\
- struct create, TypeList> { using type = typename append, typename rewrap, Types...>::type...>::type; };\
- template class Final, template class List, typename...Ts>\
- struct convert> { using type = typename append,TypeList...>::type; };
-
-#define INTERNAL_CATCH_NTTP_1(signature, ...)\
- template struct Nttp{};\
- template\
- constexpr auto get_wrapper() noexcept -> Nttp<__VA_ARGS__> { return {}; } \
- template class...> struct NttpTemplateTypeList{};\
- template class...Cs>\
- constexpr auto get_wrapper() noexcept -> NttpTemplateTypeList { return {}; } \
- \
- template< template class Container, template class List, INTERNAL_CATCH_REMOVE_PARENS(signature)>\
- struct rewrap, List<__VA_ARGS__>> { using type = TypeList>; };\
- template< template class Container, template class List, INTERNAL_CATCH_REMOVE_PARENS(signature), typename...Elements>\
- struct rewrap, List<__VA_ARGS__>, Elements...> { using type = typename append>, typename rewrap, Elements...>::type>::type; };\
- template class Final, template class...Containers, typename...Types>\
- struct create, TypeList> { using type = typename append, typename rewrap, Types...>::type...>::type; };
-
-#define INTERNAL_CATCH_DECLARE_SIG_TEST0(TestName)
-#define INTERNAL_CATCH_DECLARE_SIG_TEST1(TestName, signature)\
- template\
- static void TestName()
-#define INTERNAL_CATCH_DECLARE_SIG_TEST_X(TestName, signature, ...)\
- template\
- static void TestName()
-
-#define INTERNAL_CATCH_DEFINE_SIG_TEST0(TestName)
-#define INTERNAL_CATCH_DEFINE_SIG_TEST1(TestName, signature)\
- template\
- static void TestName()
-#define INTERNAL_CATCH_DEFINE_SIG_TEST_X(TestName, signature,...)\
- template\
- static void TestName()
-
-#define INTERNAL_CATCH_NTTP_REGISTER0(TestFunc, signature)\
- template\
- void reg_test(TypeList, Catch::NameAndTags nameAndTags)\
- {\
- Catch::AutoReg( Catch::makeTestInvoker(&TestFunc), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), nameAndTags);\
- }
-
-#define INTERNAL_CATCH_NTTP_REGISTER(TestFunc, signature, ...)\
- template\
- void reg_test(Nttp<__VA_ARGS__>, Catch::NameAndTags nameAndTags)\
- {\
- Catch::AutoReg( Catch::makeTestInvoker(&TestFunc<__VA_ARGS__>), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), nameAndTags);\
- }
-
-#define INTERNAL_CATCH_NTTP_REGISTER_METHOD0(TestName, signature, ...)\
- template\
- void reg_test(TypeList, Catch::StringRef className, Catch::NameAndTags nameAndTags)\
- {\
- Catch::AutoReg( Catch::makeTestInvoker(&TestName::test), CATCH_INTERNAL_LINEINFO, className, nameAndTags);\
- }
-
-#define INTERNAL_CATCH_NTTP_REGISTER_METHOD(TestName, signature, ...)\
- template\
- void reg_test(Nttp<__VA_ARGS__>, Catch::StringRef className, Catch::NameAndTags nameAndTags)\
- {\
- Catch::AutoReg( Catch::makeTestInvoker(&TestName<__VA_ARGS__>::test), CATCH_INTERNAL_LINEINFO, className, nameAndTags);\
- }
-
-#define INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD0(TestName, ClassName)
-#define INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD1(TestName, ClassName, signature)\
- template \
- struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName) { \
- void test();\
- }
-
-#define INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X(TestName, ClassName, signature, ...)\
- template \
- struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName)<__VA_ARGS__> { \
- void test();\
- }
-
-#define INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD0(TestName)
-#define INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD1(TestName, signature)\
- template \
- void INTERNAL_CATCH_MAKE_NAMESPACE(TestName)::TestName::test()
-#define INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X(TestName, signature, ...)\
- template \
- void INTERNAL_CATCH_MAKE_NAMESPACE(TestName)::TestName<__VA_ARGS__>::test()
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
-#define INTERNAL_CATCH_NTTP_0
-#define INTERNAL_CATCH_NTTP_GEN(...) INTERNAL_CATCH_VA_NARGS_IMPL(__VA_ARGS__, INTERNAL_CATCH_NTTP_1(__VA_ARGS__), INTERNAL_CATCH_NTTP_1(__VA_ARGS__), INTERNAL_CATCH_NTTP_1(__VA_ARGS__), INTERNAL_CATCH_NTTP_1(__VA_ARGS__), INTERNAL_CATCH_NTTP_1(__VA_ARGS__), INTERNAL_CATCH_NTTP_1( __VA_ARGS__), INTERNAL_CATCH_NTTP_1( __VA_ARGS__), INTERNAL_CATCH_NTTP_1( __VA_ARGS__), INTERNAL_CATCH_NTTP_1( __VA_ARGS__),INTERNAL_CATCH_NTTP_1( __VA_ARGS__), INTERNAL_CATCH_NTTP_0)
-#define INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD(TestName, ...) INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD1, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD0)(TestName, __VA_ARGS__)
-#define INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD(TestName, ClassName, ...) INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD1, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD0)(TestName, ClassName, __VA_ARGS__)
-#define INTERNAL_CATCH_NTTP_REG_METHOD_GEN(TestName, ...) INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD0, INTERNAL_CATCH_NTTP_REGISTER_METHOD0)(TestName, __VA_ARGS__)
-#define INTERNAL_CATCH_NTTP_REG_GEN(TestFunc, ...) INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER0, INTERNAL_CATCH_NTTP_REGISTER0)(TestFunc, __VA_ARGS__)
-#define INTERNAL_CATCH_DEFINE_SIG_TEST(TestName, ...) INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X,INTERNAL_CATCH_DEFINE_SIG_TEST_X,INTERNAL_CATCH_DEFINE_SIG_TEST1, INTERNAL_CATCH_DEFINE_SIG_TEST0)(TestName, __VA_ARGS__)
-#define INTERNAL_CATCH_DECLARE_SIG_TEST(TestName, ...) INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DECLARE_SIG_TEST_X,INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X,INTERNAL_CATCH_DECLARE_SIG_TEST_X,INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST1, INTERNAL_CATCH_DECLARE_SIG_TEST0)(TestName, __VA_ARGS__)
-#define INTERNAL_CATCH_REMOVE_PARENS_GEN(...) INTERNAL_CATCH_VA_NARGS_IMPL(__VA_ARGS__, INTERNAL_CATCH_REMOVE_PARENS_11_ARG,INTERNAL_CATCH_REMOVE_PARENS_10_ARG,INTERNAL_CATCH_REMOVE_PARENS_9_ARG,INTERNAL_CATCH_REMOVE_PARENS_8_ARG,INTERNAL_CATCH_REMOVE_PARENS_7_ARG,INTERNAL_CATCH_REMOVE_PARENS_6_ARG,INTERNAL_CATCH_REMOVE_PARENS_5_ARG,INTERNAL_CATCH_REMOVE_PARENS_4_ARG,INTERNAL_CATCH_REMOVE_PARENS_3_ARG,INTERNAL_CATCH_REMOVE_PARENS_2_ARG,INTERNAL_CATCH_REMOVE_PARENS_1_ARG)(__VA_ARGS__)
-#else
-#define INTERNAL_CATCH_NTTP_0(signature)
-#define INTERNAL_CATCH_NTTP_GEN(...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL(__VA_ARGS__, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_1,INTERNAL_CATCH_NTTP_1, INTERNAL_CATCH_NTTP_0)( __VA_ARGS__))
-#define INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD(TestName, ...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD1, INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD0)(TestName, __VA_ARGS__))
-#define INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD(TestName, ClassName, ...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X,INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD_X, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD1, INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD0)(TestName, ClassName, __VA_ARGS__))
-#define INTERNAL_CATCH_NTTP_REG_METHOD_GEN(TestName, ...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD, INTERNAL_CATCH_NTTP_REGISTER_METHOD0, INTERNAL_CATCH_NTTP_REGISTER_METHOD0)(TestName, __VA_ARGS__))
-#define INTERNAL_CATCH_NTTP_REG_GEN(TestFunc, ...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER, INTERNAL_CATCH_NTTP_REGISTER0, INTERNAL_CATCH_NTTP_REGISTER0)(TestFunc, __VA_ARGS__))
-#define INTERNAL_CATCH_DEFINE_SIG_TEST(TestName, ...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X,INTERNAL_CATCH_DEFINE_SIG_TEST_X,INTERNAL_CATCH_DEFINE_SIG_TEST1, INTERNAL_CATCH_DEFINE_SIG_TEST0)(TestName, __VA_ARGS__))
-#define INTERNAL_CATCH_DECLARE_SIG_TEST(TestName, ...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL( "dummy", __VA_ARGS__, INTERNAL_CATCH_DECLARE_SIG_TEST_X,INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DEFINE_SIG_TEST_X,INTERNAL_CATCH_DECLARE_SIG_TEST_X,INTERNAL_CATCH_DECLARE_SIG_TEST_X, INTERNAL_CATCH_DECLARE_SIG_TEST1, INTERNAL_CATCH_DECLARE_SIG_TEST0)(TestName, __VA_ARGS__))
-#define INTERNAL_CATCH_REMOVE_PARENS_GEN(...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_VA_NARGS_IMPL(__VA_ARGS__, INTERNAL_CATCH_REMOVE_PARENS_11_ARG,INTERNAL_CATCH_REMOVE_PARENS_10_ARG,INTERNAL_CATCH_REMOVE_PARENS_9_ARG,INTERNAL_CATCH_REMOVE_PARENS_8_ARG,INTERNAL_CATCH_REMOVE_PARENS_7_ARG,INTERNAL_CATCH_REMOVE_PARENS_6_ARG,INTERNAL_CATCH_REMOVE_PARENS_5_ARG,INTERNAL_CATCH_REMOVE_PARENS_4_ARG,INTERNAL_CATCH_REMOVE_PARENS_3_ARG,INTERNAL_CATCH_REMOVE_PARENS_2_ARG,INTERNAL_CATCH_REMOVE_PARENS_1_ARG)(__VA_ARGS__))
-#endif
-
-// end catch_preprocessor.hpp
-// start catch_meta.hpp
-
-
-#include
-
-namespace Catch {
- template
- struct always_false : std::false_type {};
-
- template struct true_given : std::true_type {};
- struct is_callable_tester {
- template
- true_given()(std::declval()...))> static test(int);
- template
- std::false_type static test(...);
- };
-
- template
- struct is_callable;
-
- template
- struct is_callable : decltype(is_callable_tester::test(0)) {};
-
-#if defined(__cpp_lib_is_invocable) && __cpp_lib_is_invocable >= 201703
- // std::result_of is deprecated in C++17 and removed in C++20. Hence, it is
- // replaced with std::invoke_result here.
- template
- using FunctionReturnType = std::remove_reference_t>>;
-#else
- // Keep ::type here because we still support C++11
- template
- using FunctionReturnType = typename std::remove_reference::type>::type>::type;
-#endif
-
-} // namespace Catch
-
-namespace mpl_{
- struct na;
-}
-
-// end catch_meta.hpp
-namespace Catch {
-
-template
-class TestInvokerAsMethod : public ITestInvoker {
- void (C::*m_testAsMethod)();
-public:
- TestInvokerAsMethod( void (C::*testAsMethod)() ) noexcept : m_testAsMethod( testAsMethod ) {}
-
- void invoke() const override {
- C obj;
- (obj.*m_testAsMethod)();
- }
-};
-
-auto makeTestInvoker( void(*testAsFunction)() ) noexcept -> ITestInvoker*;
-
-template
-auto makeTestInvoker( void (C::*testAsMethod)() ) noexcept -> ITestInvoker* {
- return new(std::nothrow) TestInvokerAsMethod( testAsMethod );
-}
-
-struct NameAndTags {
- NameAndTags( StringRef const& name_ = StringRef(), StringRef const& tags_ = StringRef() ) noexcept;
- StringRef name;
- StringRef tags;
-};
-
-struct AutoReg : NonCopyable {
- AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef const& classOrMethod, NameAndTags const& nameAndTags ) noexcept;
- ~AutoReg();
-};
-
-} // end namespace Catch
-
-#if defined(CATCH_CONFIG_DISABLE)
- #define INTERNAL_CATCH_TESTCASE_NO_REGISTRATION( TestName, ... ) \
- static void TestName()
- #define INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION( TestName, ClassName, ... ) \
- namespace{ \
- struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName) { \
- void test(); \
- }; \
- } \
- void TestName::test()
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( TestName, TestFunc, Name, Tags, Signature, ... ) \
- INTERNAL_CATCH_DEFINE_SIG_TEST(TestFunc, INTERNAL_CATCH_REMOVE_PARENS(Signature))
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( TestNameClass, TestName, ClassName, Name, Tags, Signature, ... ) \
- namespace{ \
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestName) { \
- INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD(TestName, ClassName, INTERNAL_CATCH_REMOVE_PARENS(Signature));\
- } \
- } \
- INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD(TestName, INTERNAL_CATCH_REMOVE_PARENS(Signature))
-
- #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(Name, Tags, ...) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ )
- #else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(Name, Tags, ...) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ ) )
- #endif
-
- #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG_NO_REGISTRATION(Name, Tags, Signature, ...) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ )
- #else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG_NO_REGISTRATION(Name, Tags, Signature, ...) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) )
- #endif
-
- #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION( ClassName, Name, Tags,... ) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ )
- #else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION( ClassName, Name, Tags,... ) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) )
- #endif
-
- #ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG_NO_REGISTRATION( ClassName, Name, Tags, Signature, ... ) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ )
- #else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG_NO_REGISTRATION( ClassName, Name, Tags, Signature, ... ) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) )
- #endif
-#endif
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TESTCASE2( TestName, ... ) \
- static void TestName(); \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( &TestName ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ __VA_ARGS__ } ); } /* NOLINT */ \
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- static void TestName()
- #define INTERNAL_CATCH_TESTCASE( ... ) \
- INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ), __VA_ARGS__ )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_METHOD_AS_TEST_CASE( QualifiedMethod, ... ) \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( &QualifiedMethod ), CATCH_INTERNAL_LINEINFO, "&" #QualifiedMethod, Catch::NameAndTags{ __VA_ARGS__ } ); } /* NOLINT */ \
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TEST_CASE_METHOD2( TestName, ClassName, ... )\
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ \
- struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName) { \
- void test(); \
- }; \
- Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar ) ( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \
- } \
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- void TestName::test()
- #define INTERNAL_CATCH_TEST_CASE_METHOD( ClassName, ... ) \
- INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_S_T_ ), ClassName, __VA_ARGS__ )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_REGISTER_TESTCASE( Function, ... ) \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( Function ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_2(TestName, TestFunc, Name, Tags, Signature, ... )\
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- INTERNAL_CATCH_DECLARE_SIG_TEST(TestFunc, INTERNAL_CATCH_REMOVE_PARENS(Signature));\
- namespace {\
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestName){\
- INTERNAL_CATCH_TYPE_GEN\
- INTERNAL_CATCH_NTTP_GEN(INTERNAL_CATCH_REMOVE_PARENS(Signature))\
- INTERNAL_CATCH_NTTP_REG_GEN(TestFunc,INTERNAL_CATCH_REMOVE_PARENS(Signature))\
- template \
- struct TestName{\
- TestName(){\
- int index = 0; \
- constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, __VA_ARGS__)};\
- using expander = int[];\
- (void)expander{(reg_test(Types{}, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index]), Tags } ), index++)... };/* NOLINT */ \
- }\
- };\
- static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\
- TestName();\
- return 0;\
- }();\
- }\
- }\
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- INTERNAL_CATCH_DEFINE_SIG_TEST(TestFunc,INTERNAL_CATCH_REMOVE_PARENS(Signature))
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE(Name, Tags, ...) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ )
-#else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE(Name, Tags, ...) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename TestType, __VA_ARGS__ ) )
-#endif
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG(Name, Tags, Signature, ...) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ )
-#else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_SIG(Name, Tags, Signature, ...) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) )
-#endif
-
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(TestName, TestFuncName, Name, Tags, Signature, TmplTypes, TypesList) \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- template static void TestFuncName(); \
- namespace {\
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestName) { \
- INTERNAL_CATCH_TYPE_GEN \
- INTERNAL_CATCH_NTTP_GEN(INTERNAL_CATCH_REMOVE_PARENS(Signature)) \
- template \
- struct TestName { \
- void reg_tests() { \
- int index = 0; \
- using expander = int[]; \
- constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TmplTypes))};\
- constexpr char const* types_list[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TypesList))};\
- constexpr auto num_types = sizeof(types_list) / sizeof(types_list[0]);\
- (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFuncName ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index / num_types]) + "<" + std::string(types_list[index % num_types]) + ">", Tags } ), index++)... };/* NOLINT */\
- } \
- }; \
- static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){ \
- using TestInit = typename create()), TypeList>::type; \
- TestInit t; \
- t.reg_tests(); \
- return 0; \
- }(); \
- } \
- } \
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- template \
- static void TestFuncName()
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE(Name, Tags, ...)\
- INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename T,__VA_ARGS__)
-#else
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE(Name, Tags, ...)\
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, typename T, __VA_ARGS__ ) )
-#endif
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_SIG(Name, Tags, Signature, ...)\
- INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2(INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__)
-#else
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_SIG(Name, Tags, Signature, ...)\
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, Signature, __VA_ARGS__ ) )
-#endif
-
- #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_2(TestName, TestFunc, Name, Tags, TmplList)\
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- template static void TestFunc(); \
- namespace {\
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestName){\
- INTERNAL_CATCH_TYPE_GEN\
- template \
- struct TestName { \
- void reg_tests() { \
- int index = 0; \
- using expander = int[]; \
- (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFunc ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ Name " - " + std::string(INTERNAL_CATCH_STRINGIZE(TmplList)) + " - " + std::to_string(index), Tags } ), index++)... };/* NOLINT */\
- } \
- };\
- static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){ \
- using TestInit = typename convert::type; \
- TestInit t; \
- t.reg_tests(); \
- return 0; \
- }(); \
- }}\
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- template \
- static void TestFunc()
-
- #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE(Name, Tags, TmplList) \
- INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), Name, Tags, TmplList )
-
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( TestNameClass, TestName, ClassName, Name, Tags, Signature, ... ) \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- namespace {\
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestName){ \
- INTERNAL_CATCH_TYPE_GEN\
- INTERNAL_CATCH_NTTP_GEN(INTERNAL_CATCH_REMOVE_PARENS(Signature))\
- INTERNAL_CATCH_DECLARE_SIG_TEST_METHOD(TestName, ClassName, INTERNAL_CATCH_REMOVE_PARENS(Signature));\
- INTERNAL_CATCH_NTTP_REG_METHOD_GEN(TestName, INTERNAL_CATCH_REMOVE_PARENS(Signature))\
- template \
- struct TestNameClass{\
- TestNameClass(){\
- int index = 0; \
- constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, __VA_ARGS__)};\
- using expander = int[];\
- (void)expander{(reg_test(Types{}, #ClassName, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index]), Tags } ), index++)... };/* NOLINT */ \
- }\
- };\
- static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\
- TestNameClass();\
- return 0;\
- }();\
- }\
- }\
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- INTERNAL_CATCH_DEFINE_SIG_TEST_METHOD(TestName, INTERNAL_CATCH_REMOVE_PARENS(Signature))
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( ClassName, Name, Tags,... ) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ )
-#else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( ClassName, Name, Tags,... ) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, typename T, __VA_ARGS__ ) )
-#endif
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... ) \
- INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ )
-#else
- #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... ) \
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_C_L_A_S_S_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ) , ClassName, Name, Tags, Signature, __VA_ARGS__ ) )
-#endif
-
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2(TestNameClass, TestName, ClassName, Name, Tags, Signature, TmplTypes, TypesList)\
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- template \
- struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName ) { \
- void test();\
- };\
- namespace {\
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestNameClass) {\
- INTERNAL_CATCH_TYPE_GEN \
- INTERNAL_CATCH_NTTP_GEN(INTERNAL_CATCH_REMOVE_PARENS(Signature))\
- template\
- struct TestNameClass{\
- void reg_tests(){\
- int index = 0;\
- using expander = int[];\
- constexpr char const* tmpl_types[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TmplTypes))};\
- constexpr char const* types_list[] = {CATCH_REC_LIST(INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS, INTERNAL_CATCH_REMOVE_PARENS(TypesList))};\
- constexpr auto num_types = sizeof(types_list) / sizeof(types_list[0]);\
- (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ Name " - " + std::string(tmpl_types[index / num_types]) + "<" + std::string(types_list[index % num_types]) + ">", Tags } ), index++)... };/* NOLINT */ \
- }\
- };\
- static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\
- using TestInit = typename create()), TypeList>::type;\
- TestInit t;\
- t.reg_tests();\
- return 0;\
- }(); \
- }\
- }\
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- template \
- void TestName::test()
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD( ClassName, Name, Tags, ... )\
- INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, typename T, __VA_ARGS__ )
-#else
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD( ClassName, Name, Tags, ... )\
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, typename T,__VA_ARGS__ ) )
-#endif
-
-#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... )\
- INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, Signature, __VA_ARGS__ )
-#else
- #define INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_SIG( ClassName, Name, Tags, Signature, ... )\
- INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_PRODUCT_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, Signature,__VA_ARGS__ ) )
-#endif
-
- #define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD_2( TestNameClass, TestName, ClassName, Name, Tags, TmplList) \
- CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \
- template \
- struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName ) { \
- void test();\
- };\
- namespace {\
- namespace INTERNAL_CATCH_MAKE_NAMESPACE(TestName){ \
- INTERNAL_CATCH_TYPE_GEN\
- template\
- struct TestNameClass{\
- void reg_tests(){\
- int index = 0;\
- using expander = int[];\
- (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ Name " - " + std::string(INTERNAL_CATCH_STRINGIZE(TmplList)) + " - " + std::to_string(index), Tags } ), index++)... };/* NOLINT */ \
- }\
- };\
- static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\
- using TestInit = typename convert::type;\
- TestInit t;\
- t.reg_tests();\
- return 0;\
- }(); \
- }}\
- CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION \
- template \
- void TestName::test()
-
-#define INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD(ClassName, Name, Tags, TmplList) \
- INTERNAL_CATCH_TEMPLATE_LIST_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_ ), INTERNAL_CATCH_UNIQUE_NAME( C_A_T_C_H_T_E_M_P_L_A_T_E_T_E_S_T_F_U_N_C_ ), ClassName, Name, Tags, TmplList )
-
-// end catch_test_registry.h
-// start catch_capture.hpp
-
-// start catch_assertionhandler.h
-
-// start catch_assertioninfo.h
-
-// start catch_result_type.h
-
-namespace Catch {
-
- // ResultWas::OfType enum
- struct ResultWas { enum OfType {
- Unknown = -1,
- Ok = 0,
- Info = 1,
- Warning = 2,
-
- FailureBit = 0x10,
-
- ExpressionFailed = FailureBit | 1,
- ExplicitFailure = FailureBit | 2,
-
- Exception = 0x100 | FailureBit,
-
- ThrewException = Exception | 1,
- DidntThrowException = Exception | 2,
-
- FatalErrorCondition = 0x200 | FailureBit
-
- }; };
-
- bool isOk( ResultWas::OfType resultType );
- bool isJustInfo( int flags );
-
- // ResultDisposition::Flags enum
- struct ResultDisposition { enum Flags {
- Normal = 0x01,
-
- ContinueOnFailure = 0x02, // Failures fail test, but execution continues
- FalseTest = 0x04, // Prefix expression with !
- SuppressFail = 0x08 // Failures are reported but do not fail the test
- }; };
-
- ResultDisposition::Flags operator | ( ResultDisposition::Flags lhs, ResultDisposition::Flags rhs );
-
- bool shouldContinueOnFailure( int flags );
- inline bool isFalseTest( int flags ) { return ( flags & ResultDisposition::FalseTest ) != 0; }
- bool shouldSuppressFailure( int flags );
-
-} // end namespace Catch
-
-// end catch_result_type.h
-namespace Catch {
-
- struct AssertionInfo
- {
- StringRef macroName;
- SourceLineInfo lineInfo;
- StringRef capturedExpression;
- ResultDisposition::Flags resultDisposition;
-
- // We want to delete this constructor but a compiler bug in 4.8 means
- // the struct is then treated as non-aggregate
- //AssertionInfo() = delete;
- };
-
-} // end namespace Catch
-
-// end catch_assertioninfo.h
-// start catch_decomposer.h
-
-// start catch_tostring.h
-
-#include
-#include
-#include
-#include
-// start catch_stream.h
-
-#include
-#include
-#include
-
-namespace Catch {
-
- std::ostream& cout();
- std::ostream& cerr();
- std::ostream& clog();
-
- class StringRef;
-
- struct IStream {
- virtual ~IStream();
- virtual std::ostream& stream() const = 0;
- };
-
- auto makeStream( StringRef const &filename ) -> IStream const*;
-
- class ReusableStringStream : NonCopyable {
- std::size_t m_index;
- std::ostream* m_oss;
- public:
- ReusableStringStream();
- ~ReusableStringStream();
-
- auto str() const -> std::string;
-
- template
- auto operator << ( T const& value ) -> ReusableStringStream& {
- *m_oss << value;
- return *this;
- }
- auto get() -> std::ostream& { return *m_oss; }
- };
-}
-
-// end catch_stream.h
-// start catch_interfaces_enum_values_registry.h
-
-#include
-
-namespace Catch {
-
- namespace Detail {
- struct EnumInfo {
- StringRef m_name;
- std::vector> m_values;
-
- ~EnumInfo();
-
- StringRef lookup( int value ) const;
- };
- } // namespace Detail
-
- struct IMutableEnumValuesRegistry {
- virtual ~IMutableEnumValuesRegistry();
-
- virtual Detail::EnumInfo const& registerEnum( StringRef enumName, StringRef allEnums, std::vector const& values ) = 0;
-
- template
- Detail::EnumInfo const& registerEnum( StringRef enumName, StringRef allEnums, std::initializer_list values ) {
- static_assert(sizeof(int) >= sizeof(E), "Cannot serialize enum to int");
- std::vector intValues;
- intValues.reserve( values.size() );
- for( auto enumValue : values )
- intValues.push_back( static_cast( enumValue ) );
- return registerEnum( enumName, allEnums, intValues );
- }
- };
-
-} // Catch
-
-// end catch_interfaces_enum_values_registry.h
-
-#ifdef CATCH_CONFIG_CPP17_STRING_VIEW
-#include
-#endif
-
-#ifdef __OBJC__
-// start catch_objc_arc.hpp
-
-#import
-
-#ifdef __has_feature
-#define CATCH_ARC_ENABLED __has_feature(objc_arc)
-#else
-#define CATCH_ARC_ENABLED 0
-#endif
-
-void arcSafeRelease( NSObject* obj );
-id performOptionalSelector( id obj, SEL sel );
-
-#if !CATCH_ARC_ENABLED
-inline void arcSafeRelease( NSObject* obj ) {
- [obj release];
-}
-inline id performOptionalSelector( id obj, SEL sel ) {
- if( [obj respondsToSelector: sel] )
- return [obj performSelector: sel];
- return nil;
-}
-#define CATCH_UNSAFE_UNRETAINED
-#define CATCH_ARC_STRONG
-#else
-inline void arcSafeRelease( NSObject* ){}
-inline id performOptionalSelector( id obj, SEL sel ) {
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Warc-performSelector-leaks"
-#endif
- if( [obj respondsToSelector: sel] )
- return [obj performSelector: sel];
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
- return nil;
-}
-#define CATCH_UNSAFE_UNRETAINED __unsafe_unretained
-#define CATCH_ARC_STRONG __strong
-#endif
-
-// end catch_objc_arc.hpp
-#endif
-
-#ifdef _MSC_VER
-#pragma warning(push)
-#pragma warning(disable:4180) // We attempt to stream a function (address) by const&, which MSVC complains about but is harmless
-#endif
-
-namespace Catch {
- namespace Detail {
-
- extern const std::string unprintableString;
-
- std::string rawMemoryToString( const void *object, std::size_t size );
-
- template
- std::string rawMemoryToString( const T& object ) {
- return rawMemoryToString( &object, sizeof(object) );
- }
-
- template
- class IsStreamInsertable {
- template
- static auto test(int)
- -> decltype(std::declval() << std::declval(), std::true_type());
-
- template
- static auto test(...)->std::false_type;
-
- public:
- static const bool value = decltype(test(0))::value;
- };
-
- template
- std::string convertUnknownEnumToString( E e );
-
- template
- typename std::enable_if<
- !std::is_enum::value && !std::is_base_of::value,
- std::string>::type convertUnstreamable( T const& ) {
- return Detail::unprintableString;
- }
- template
- typename std::enable_if<
- !std::is_enum::value && std::is_base_of::value,
- std::string>::type convertUnstreamable(T const& ex) {
- return ex.what();
- }
-
- template
- typename std::enable_if<
- std::is_enum::value
- , std::string>::type convertUnstreamable( T const& value ) {
- return convertUnknownEnumToString( value );
- }
-
-#if defined(_MANAGED)
- //! Convert a CLR string to a utf8 std::string
- template
- std::string clrReferenceToString( T^ ref ) {
- if (ref == nullptr)
- return std::string("null");
- auto bytes = System::Text::Encoding::UTF8->GetBytes(ref->ToString());
- cli::pin_ptr p = &bytes[0];
- return std::string(reinterpret_cast(p), bytes->Length);
- }
-#endif
-
- } // namespace Detail
-
- // If we decide for C++14, change these to enable_if_ts
- template
- struct StringMaker {
- template
- static
- typename std::enable_if<::Catch::Detail::IsStreamInsertable::value, std::string>::type
- convert(const Fake& value) {
- ReusableStringStream rss;
- // NB: call using the function-like syntax to avoid ambiguity with
- // user-defined templated operator<< under clang.
- rss.operator<<(value);
- return rss.str();
- }
-
- template
- static
- typename std::enable_if::value, std::string>::type
- convert( const Fake& value ) {
-#if !defined(CATCH_CONFIG_FALLBACK_STRINGIFIER)
- return Detail::convertUnstreamable(value);
-#else
- return CATCH_CONFIG_FALLBACK_STRINGIFIER(value);
-#endif
- }
- };
-
- namespace Detail {
-
- // This function dispatches all stringification requests inside of Catch.
- // Should be preferably called fully qualified, like ::Catch::Detail::stringify
- template
- std::string stringify(const T& e) {
- return ::Catch::StringMaker::type>::type>::convert(e);
- }
-
- template
- std::string convertUnknownEnumToString( E e ) {
- return ::Catch::Detail::stringify(static_cast::type>(e));
- }
-
-#if defined(_MANAGED)
- template
- std::string stringify( T^ e ) {
- return ::Catch::StringMaker::convert(e);
- }
-#endif
-
- } // namespace Detail
-
- // Some predefined specializations
-
- template<>
- struct StringMaker {
- static std::string convert(const std::string& str);
- };
-
-#ifdef CATCH_CONFIG_CPP17_STRING_VIEW
- template<>
- struct StringMaker {
- static std::string convert(std::string_view str);
- };
-#endif
-
- template<>
- struct StringMaker {
- static std::string convert(char const * str);
- };
- template<>
- struct StringMaker {
- static std::string convert(char * str);
- };
-
-#ifdef CATCH_CONFIG_WCHAR
- template<>
- struct StringMaker {
- static std::string convert(const std::wstring& wstr);
- };
-
-# ifdef CATCH_CONFIG_CPP17_STRING_VIEW
- template<>
- struct StringMaker {
- static std::string convert(std::wstring_view str);
- };
-# endif
-
- template<>
- struct StringMaker {
- static std::string convert(wchar_t const * str);
- };
- template<>
- struct StringMaker {
- static std::string convert(wchar_t * str);
- };
-#endif
-
- // TBD: Should we use `strnlen` to ensure that we don't go out of the buffer,
- // while keeping string semantics?
- template
- struct StringMaker {
- static std::string convert(char const* str) {
- return ::Catch::Detail::stringify(std::string{ str });
- }
- };
- template
- struct StringMaker {
- static std::string convert(signed char const* str) {
- return ::Catch::Detail::stringify(std::string{ reinterpret_cast(str) });
- }
- };
- template